Go to the documentation of this file.00001
00002 #include <ros/ros.h>
00003
00004
00005 #include "laser_assembler/AssembleScans2.h"
00006
00007
00008 #include "sensor_msgs/PointCloud2.h"
00009 #include "sensor_msgs/JointState.h"
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021 namespace atlas_laser_snapshotter
00022 {
00023
00024 class AtlasLaserSnapshotter
00025 {
00026
00027 public:
00028 ros::NodeHandle n_;
00029 ros::NodeHandle private_ns_;
00030 ros::Publisher pub_;
00031 ros::Subscriber sub_;
00032
00033 ros::Time prev_signal_;
00034 double prev_angle_;
00035
00036 bool first_time_;
00037
00038 int num_skips_;
00039 int num_skips_left_;
00040
00041 std::string fixed_frame_;
00042
00043 AtlasLaserSnapshotter() : private_ns_("~")
00044 {
00045 prev_signal_.fromNSec(0);
00046
00047 pub_ = n_.advertise<sensor_msgs::PointCloud2> ("full_cloud2", 1);
00048 sub_ = n_.subscribe("joint_states", 40, &AtlasLaserSnapshotter::scannerSignalCallback, this);
00049
00050 private_ns_.param("num_skips", num_skips_, 0);
00051 num_skips_left_=num_skips_;
00052
00053 prev_angle_ = -1;
00054 first_time_ = true;
00055 }
00056
00057 ~AtlasLaserSnapshotter()
00058 {
00059
00060 }
00061
00062 void scannerSignalCallback(const sensor_msgs::JointStateConstPtr& js)
00063 {
00064
00065 double ang = fmod(js->position[0], 2 * M_PI);
00066
00067
00068 if ( prev_angle_ < 0 ) {
00069 prev_angle_ = ang;
00070 return;
00071 }
00072 if ((ang - prev_angle_) >= - M_PI) {
00073 prev_angle_ = ang;
00074 return;
00075 }
00076
00077 if (prev_signal_.toSec() == 0.0) {
00078 first_time_ = true;
00079 }
00080
00081 ros::Time stmp = js->header.stamp;
00082 if (first_time_)
00083 {
00084 prev_signal_ = stmp;
00085 first_time_ = false;
00086 }
00087 else
00088 {
00089 if (num_skips_ > 0)
00090 {
00091 if (num_skips_left_ > 0)
00092 {
00093 num_skips_left_ -= 1;
00094 return;
00095 }
00096 else
00097 {
00098 num_skips_left_ = num_skips_;
00099 }
00100 }
00101
00102 laser_assembler::AssembleScans2::Request req;
00103 laser_assembler::AssembleScans2::Response res;
00104
00105 req.begin = prev_signal_;
00106 req.end = stmp;
00107
00108 if (!ros::service::call("assemble_scans2", req, res))
00109 ROS_ERROR("Failed to call service on point cloud assembler or laser scan assembler.");
00110
00111 pub_.publish(res.cloud);
00112 ROS_INFO("Snapshotter::Published Cloud size=%u", res.cloud.width * res.cloud.height);
00113
00114 prev_signal_ = stmp;
00115 prev_angle_ = -1;
00116 }
00117 }
00118 };
00119 }
00120
00121 using namespace atlas_laser_snapshotter;
00122
00123 int main(int argc, char **argv)
00124 {
00125 ros::init(argc, argv, "atlas_laser_snapshotter");
00126 AtlasLaserSnapshotter snapshotter ;
00127 ros::spin();
00128 return 0;
00129 }