Skip to content
Snippets Groups Projects
Commit 76c9e314 authored by Reed Hedges's avatar Reed Hedges
Browse files

Remove any "." characters from topic/tf names (not allowed)

parent 347503e9
No related branches found
No related tags found
No related merge requests found
......@@ -10,6 +10,8 @@
#include <math.h>
#include <boost/algorithm/string.hpp>
// TODO publish pointcloud of cumulative readings in separate topic?
// TODO generic pointcloud sensor publisher (seprate point cloud stuff there)
// TODO make similar sonar publisher?
......@@ -28,8 +30,10 @@ LaserPublisher::LaserPublisher(ArLaser *_l, ros::NodeHandle& _n, bool _broadcast
laser->addReadingCB(&laserReadingsCB);
laser->unlockDevice();
std::string laserscan_name(laser->getName());
boost::erase_all(laserscan_name,".");
laserscan_name += "_laserscan";
std::string pointcloud_name(laser->getName());
boost::erase_all(pointcloud_name,".");
pointcloud_name += "_pointcloud";
laserscan_pub = node.advertise<sensor_msgs::LaserScan>(laserscan_name, 20);
pointcloud_pub = node.advertise<sensor_msgs::PointCloud>(pointcloud_name, 50);
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment