13 #include <boost/algorithm/string.hpp> 24 parenttfname(_parent_tf_frame),
25 globaltfname(_global_tf_frame),
26 broadcast_tf(_broadcast_tf)
31 laser->unlockDevice();
32 std::string laserscan_name(
laser->getName());
33 boost::erase_all(laserscan_name,
".");
34 laserscan_name +=
"_laserscan";
35 std::string pointcloud_name(
laser->getName());
36 boost::erase_all(pointcloud_name,
".");
37 pointcloud_name +=
"_pointcloud";
42 if(
laser->hasSensorPosition())
45 q.setRPY(0, 0, ArMath::degToRad(
laser->getSensorPositionTh()));
55 laserscan.header.frame_id =
"laser_frame";
65 if(
laser->canSetIncrement()) {
68 else if(
laser->getIncrementChoice() != NULL) {
81 laser->unlockDevice();
92 laser->unlockDevice();
101 const std::list<ArSensorReading*> *readings =
laser->getRawReadings();
104 laserscan.ranges.resize(readings->size());
106 if (
laser->getFlipped()) {
108 for(std::list<ArSensorReading*>::const_reverse_iterator r = readings->rbegin(); r != readings->rend(); ++r)
112 if ((*r)->getIgnoreThisReading()) {
116 laserscan.ranges[n] = (*r)->getRange() / 1000.0;
123 for(std::list<ArSensorReading*>::const_iterator r = readings->begin(); r != readings->end(); ++r)
127 if ((*r)->getIgnoreThisReading()) {
131 laserscan.ranges[n] = (*r)->getRange() / 1000.0;
145 assert(
laser->getCurrentBuffer());
146 const std::list<ArPoseWithTime*> *p =
laser->getCurrentRangeBuffer()->getBuffer();
150 for(std::list<ArPoseWithTime*>::const_iterator i = p->begin(); i != p->end(); ++i)
153 pointcloud.points[n].x = (*i)->getX() / 1000.0;
154 pointcloud.points[n].y = (*i)->getY() / 1000.0;
155 pointcloud.points[n].z = (
laser->hasSensorPosition() ?
laser->getSensorPositionZ() / 1000.0 : 0.0);
ArFunctorC< LaserPublisher > laserReadingsCB
LaserPublisher(ArLaser *_l, ros::NodeHandle &_n, bool _broadcast_transform=true, const std::string &_tf_frame="laser", const std::string &_parent_tf_frame="base_link", const std::string &_global_tf_frame="odom")
sensor_msgs::LaserScan laserscan
void publish(const boost::shared_ptr< M > &message) const
tf::TransformBroadcaster transform_broadcaster
sensor_msgs::PointCloud pointcloud
ros::Time convertArTimeToROS(const ArTime &t)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Publisher laserscan_pub
ros::Publisher pointcloud_pub