Skip to content

Commit

Permalink
Merge pull request #21 from jcmonteiro/feature/offline/increase-publi…
Browse files Browse the repository at this point in the history
…sher-queue-length

Add the publishers' queue length as a parameter when replaying offline
  • Loading branch information
eupedrosa authored Nov 19, 2020
2 parents 728c945 + 4cdd88e commit fc35175
Showing 1 changed file with 6 additions and 4 deletions.
10 changes: 6 additions & 4 deletions src/offline_replay.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,8 @@ void lama::ReplayRosbag(ros::NodeHandle& pnh, const std::string& rosbag_filename
{
std::string scan_topic;
pnh.param("scan_topic", scan_topic, std::string("/scan"));
int queue_length;
pnh.param("queue_length", queue_length, 100);

ROS_INFO("Scan topic: %s", scan_topic.c_str());

Expand All @@ -59,10 +61,10 @@ void lama::ReplayRosbag(ros::NodeHandle& pnh, const std::string& rosbag_filename
ROS_FATAL("Unable to open rosbag [%s]: %s", rosbag_filename.c_str(), ex.what());
}

auto pub_scan = pnh.advertise<sensor_msgs::LaserScan>(scan_topic,10);
auto pub_tf = pnh.advertise<tf2_msgs::TFMessage>("/tf",10);
auto pub_tf_static = pnh.advertise<tf2_msgs::TFMessage>("/tf_static",10, true);
auto pub_clock = pnh.advertise<rosgraph_msgs::Clock>("/clock",10);
auto pub_scan = pnh.advertise<sensor_msgs::LaserScan>(scan_topic, queue_length);
auto pub_tf = pnh.advertise<tf2_msgs::TFMessage>("/tf", queue_length);
auto pub_tf_static = pnh.advertise<tf2_msgs::TFMessage>("/tf_static", queue_length, true);
auto pub_clock = pnh.advertise<rosgraph_msgs::Clock>("/clock", queue_length);

ROS_INFO("Allow time for the subscribers to connect");
ros::WallDuration wait(2); wait.sleep();
Expand Down

0 comments on commit fc35175

Please sign in to comment.