40 #include "sensor_msgs/LaserScan.h" 41 #include "calibration_msgs/DenseLaserSnapshot.h" 42 #include "pr2_msgs/LaserScannerSignal.h" 56 assembler_.setCacheSize(40*20);
57 prev_signal_.header.stamp =
ros::Time(0, 0);
60 snapshot_pub_ = n_.advertise<calibration_msgs::DenseLaserSnapshot> (
"dense_laser_snapshot", 1);
80 prev_signal_ = *cur_signal ;
85 if (cur_signal->signal == 1)
92 calibration_msgs::DenseLaserSnapshot snapshot;
94 assembler_.assembleSnapshot(start, end, snapshot);
96 ROS_DEBUG(
"header.stamp: %f", snapshot.header.stamp.toSec());
97 ROS_DEBUG(
"header.frame_id: %s", snapshot.header.frame_id.c_str());
98 ROS_DEBUG(
"ranges.size()=%lu", snapshot.ranges.size());
99 ROS_DEBUG(
"intensities.size()=%lu", snapshot.intensities.size());
100 ROS_DEBUG(
"scan_start.size()=%lu", snapshot.scan_start.size());
101 snapshot_pub_.publish(snapshot);
105 prev_signal_ = *cur_signal;
120 int main(
int argc,
char **argv)
122 ros::init(argc, argv,
"dense_laser_snapshotter") ;
int main(int argc, char **argv)
ros::Subscriber scan_sub_
Builds a DenseLaserSnapshot message from laser scans collected in a specified time interval...
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::Subscriber signal_sub_
pr2_msgs::LaserScannerSignal prev_signal_
ros::Publisher snapshot_pub_
DenseLaserAssembler assembler_
void scannerSignalCallback(const pr2_msgs::LaserScannerSignalConstPtr &cur_signal)
void scanCallback(const sensor_msgs::LaserScanConstPtr &scan)