Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #include <cstdio>
00036 #include <math.h>
00037 #include <ros/ros.h>
00038 #include <sensor_msgs/JointState.h>
00039
00040
00041 #include "laser_assembler/AssembleScans2.h"
00042
00043
00044 #include "sensor_msgs/PointCloud2.h"
00045
00046
00047
00048
00049
00050
00051 namespace laser_assembler
00052 {
00053
00054 class PeriodicSnapshotter
00055 {
00056
00057 public:
00058
00059 PeriodicSnapshotter()
00060 {
00061
00062 pub_ = n_.advertise<sensor_msgs::PointCloud2> ("assembled_cloud", 1);
00063
00064 sub_ = n_.subscribe("joint_states", 1000, &PeriodicSnapshotter::rotCallback, this);
00065
00066
00067 client_ = n_.serviceClient<AssembleScans2>("assemble_scans2");
00068
00069 first_time_ = true;
00070 arm_ = false;
00071 }
00072
00076 int getIndex(const sensor_msgs::JointState::ConstPtr& e)
00077 {
00078 for (size_t i = 0; i < e->name.size(); ++i)
00079 {
00080 if (e->name[i] == "laser_rot_joint")
00081 return i;
00082 }
00083 return -1;
00084 }
00085
00086 void rotCallback(const sensor_msgs::JointState::ConstPtr& e)
00087 {
00088
00089 if(first_time_) {
00090 last_time_ = e->header.stamp;
00091 first_time_ = false;
00092 return;
00093 }
00094
00095 int index = getIndex(e);
00096 if (index < 0)
00097 return;
00098
00099 double position = fmod(e->position[index], 2 * M_PI);
00100
00101 if (!arm_ && position > 3) {
00102 arm_ = true;
00103 return;
00104 }
00105
00106 if(arm_ && position > 0 && position < 1) {
00107
00108
00109 AssembleScans2 srv;
00110 srv.request.begin = last_time_;
00111 srv.request.end = e->header.stamp;
00112
00113
00114 if (client_.call(srv))
00115 {
00116 ROS_INFO("Published Cloud with %u points", srv.response.cloud.width * srv.response.cloud.height) ;
00117 pub_.publish(srv.response.cloud);
00118 }
00119 else
00120 {
00121 ROS_ERROR("Error making service call\n") ;
00122 }
00123
00124 arm_ = false;
00125 last_time_ = e->header.stamp;
00126 }
00127 }
00128
00129 private:
00130 ros::NodeHandle n_;
00131 ros::Publisher pub_;
00132 ros::Subscriber sub_;
00133 ros::ServiceClient client_;
00134 bool first_time_;
00135 bool arm_;
00136 ros::Time last_time_;
00137 } ;
00138
00139 }
00140
00141 using namespace laser_assembler ;
00142
00143 int main(int argc, char **argv)
00144 {
00145 ros::init(argc, argv, "rotunit_snapshotter");
00146 ros::NodeHandle n;
00147 ROS_INFO("Waiting for [assemble_scans2] to be advertised");
00148 ros::service::waitForService("assemble_scans2");
00149 ROS_INFO("Found assemble_scans2! Starting the snapshotter");
00150 PeriodicSnapshotter snapshotter;
00151 ros::spin();
00152 return 0;
00153 }