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 #include <ros/ros.h>
00031
00032
00033 #include <actionlib/server/action_server.h>
00034 #include <pr2_tilt_laser_interface/GetSnapshotAction.h>
00035
00036
00037 #include <pr2_msgs/SetLaserTrajCmd.h>
00038
00039
00040 #include <sensor_msgs/LaserScan.h>
00041 #include <laser_geometry/laser_geometry.h>
00042 #include <pcl_ros/transforms.h>
00043
00044 #include <tf/transform_listener.h>
00045 #include "tf/message_filter.h"
00046 #include <message_filters/subscriber.h>
00047 #include <pcl/io/io.h>
00048
00049 void appendCloud(sensor_msgs::PointCloud2& dest, const sensor_msgs::PointCloud2& src)
00050 {
00051
00052 dest.height += 1;
00053
00054 size_t start = dest.data.size ();
00055
00056 if (start == 0)
00057 {
00058 dest = src;
00059 return;
00060 }
00061
00062 dest.data.resize (start + src.data.size ());
00063 memcpy (&dest.data[start], &src.data[0], src.data.size ());
00064
00065
00066 int time_index = src.fields[pcl::getFieldIndex (dest, "timestamp")].offset;
00067 float time_offset = src.header.stamp.toSec () - dest.header.stamp.toSec ();
00068 float* time_ptr;
00069 for (size_t i = 0; i < src.width * src.height; ++i)
00070 {
00071 time_ptr = (float*) &dest.data[start + i * src.point_step + time_index];
00072 *time_ptr += time_offset;
00073 }
00074 }
00075
00076 using namespace pr2_tilt_laser_interface;
00077
00078 namespace SnapshotStates
00079 {
00080 enum SnapshotState
00081 {
00082 COLLECTING = 1,
00083 IDLE = 2
00084 };
00085 }
00086 typedef SnapshotStates::SnapshotState SnapshotState;
00087
00088 typedef actionlib::ActionServer<GetSnapshotAction> SnapshotActionServer;
00089
00090 class Snapshotter
00091 {
00092 public:
00093 Snapshotter();
00094
00095 void startScan(double move_to_start_wait_time=1.0);
00096
00097 void scanCallback(const sensor_msgs::LaserScanConstPtr& scan);
00098
00099
00100 void goalCallback(SnapshotActionServer::GoalHandle gh);
00101 void cancelCallback(SnapshotActionServer::GoalHandle gh);
00102
00103 private:
00104 ros::NodeHandle nh_;
00105 SnapshotActionServer as_;
00106
00107 message_filters::Subscriber<sensor_msgs::LaserScan> scan_sub_;
00108 ros::ServiceClient laser_controller_sc_;
00109
00110 boost::mutex state_mutex_;
00111 SnapshotState state_;
00112 ros::Time interval_start_;
00113 ros::Time interval_end_;
00114 laser_geometry::LaserProjection lg_;
00115 GetSnapshotResult snapshot_result_;
00116 GetSnapshotFeedback snapshot_feedback_;
00117
00118 SnapshotActionServer::GoalHandle current_gh_;
00119 GetSnapshotGoal goal_;
00120
00121 tf::TransformListener tf_;
00122 std::string fixed_frame_;
00123 boost::scoped_ptr<tf::MessageFilter<sensor_msgs::LaserScan> > tf_filter_;
00124
00125 };
00126
00127 Snapshotter::Snapshotter() :
00128 as_(nh_, "get_laser_snapshot", false),
00129 state_(SnapshotStates::IDLE),
00130 tf_(nh_)
00131 {
00132 as_.registerGoalCallback( boost::bind(&Snapshotter::goalCallback, this, _1) );
00133 as_.registerCancelCallback( boost::bind(&Snapshotter::cancelCallback, this, _1) );
00134
00135
00136
00137 laser_controller_sc_ = nh_.serviceClient<pr2_msgs::SetLaserTrajCmd>("laser_tilt_controller/set_traj_cmd");
00138
00139
00140 ros::NodeHandle private_ns_("~");
00141 if (!private_ns_.getParam("fixed_frame", fixed_frame_))
00142 ROS_FATAL("Need to set parameter ~fixed_frame");
00143 ROS_DEBUG("Using fixed frame [%s]", fixed_frame_.c_str());
00144
00145
00146 scan_sub_.subscribe(nh_, "tilt_scan", 10);
00147 tf_filter_.reset( new tf::MessageFilter<sensor_msgs::LaserScan>(scan_sub_, tf_, fixed_frame_, 10) );
00148 tf_filter_->setTolerance(ros::Duration(0.025));
00149 tf_filter_->registerCallback( boost::bind(&Snapshotter::scanCallback, this, _1) );
00150
00151
00152 as_.start();
00153 }
00154
00155 void Snapshotter::scanCallback(const sensor_msgs::LaserScanConstPtr& scan)
00156 {
00157 boost::mutex::scoped_lock lock(state_mutex_);
00158
00159 if (state_ == SnapshotStates::IDLE)
00160 return;
00161
00162 sensor_msgs::PointCloud2& cloud = (goal_.continuous ? snapshot_feedback_.cloud : snapshot_result_.cloud);
00163
00164 if (state_ == SnapshotStates::COLLECTING)
00165 {
00166 if (scan->header.stamp < interval_start_)
00167 {
00168 ROS_DEBUG("Waiting to get to the start of the interval");
00169
00170 return;
00171 }
00172 else if (scan->header.stamp < interval_end_)
00173 {
00174
00175 ROS_DEBUG("In the actual interval");
00176 sensor_msgs::PointCloud2 cur_cloud_tf;
00177
00178 if (!goal_.hi_fidelity)
00179 {
00180 sensor_msgs::PointCloud2 cur_cloud;
00181 lg_.projectLaser (*scan, cur_cloud);
00182 tf::StampedTransform net_transform;
00183 tf_.lookupTransform (fixed_frame_, cur_cloud.header.frame_id, cur_cloud.header.stamp, net_transform);
00184 pcl_ros::transformPointCloud (fixed_frame_, net_transform, cur_cloud, cur_cloud_tf);
00185 }
00186 else
00187 {
00188 lg_.transformLaserScanToPointCloud (fixed_frame_, *scan, cur_cloud_tf, tf_);
00189 }
00190 appendCloud (cloud, cur_cloud_tf);
00191 }
00192 else
00193 {
00194 ROS_DEBUG ("Bundling everything up and publishing cloud with %u points", cloud.width * cloud.width);
00195
00196 state_ = SnapshotStates::IDLE;
00197
00198 if (goal_.continuous)
00199 {
00200
00201 current_gh_.publishFeedback (snapshot_feedback_);
00202 std::swap(goal_.start_angle, goal_.end_angle);
00203 startScan(0.1);
00204 }
00205 else
00206 {
00207 current_gh_.setSucceeded (snapshot_result_);
00208 }
00209 cloud.data.clear ();
00210 }
00211 }
00212 else
00213 ROS_ERROR("In an unknown state. This is a programming error");
00214
00215 }
00216
00217 void Snapshotter::goalCallback(SnapshotActionServer::GoalHandle gh)
00218 {
00219 boost::mutex::scoped_lock lock(state_mutex_);
00220
00221
00222 if (state_ != SnapshotStates::IDLE)
00223 {
00224 current_gh_.setCanceled();
00225 state_ = SnapshotStates::IDLE;
00226 }
00227
00228 current_gh_ = gh;
00229 current_gh_.setAccepted();
00230
00231 goal_ = *current_gh_.getGoal();
00232
00233 startScan();
00234 }
00235
00236 void Snapshotter::startScan(double move_to_start_wait_time)
00237 {
00238
00239
00240
00241
00242 pr2_msgs::LaserTrajCmd cmd;
00243
00244 cmd.profile = "linear";
00245 cmd.position.resize(4);
00246 cmd.position[0] = goal_.start_angle;
00247 cmd.position[1] = goal_.start_angle;
00248 cmd.position[2] = goal_.end_angle;
00249 cmd.position[3] = (goal_.continuous ? goal_.end_angle : goal_.start_angle);
00250
00251 if (goal_.speed==0.0)
00252 {
00253 ROS_ERROR("Scan speed is set to zero -> aborting!\n");
00254 return;
00255 }
00256
00257 ros::Duration scan_duration( (goal_.start_angle - goal_.end_angle)/goal_.speed );
00258 if (scan_duration.toSec() < 0.0)
00259 scan_duration = -scan_duration;
00260
00261 ros::Duration wait_time(move_to_start_wait_time);
00262 cmd.time_from_start.resize(4);
00263 cmd.time_from_start[0] = ros::Duration(0.0);
00264 cmd.time_from_start[1] = wait_time;
00265 cmd.time_from_start[2] = wait_time + scan_duration;
00266 cmd.time_from_start[3] = wait_time + scan_duration + scan_duration;
00267 cmd.max_velocity = 0;
00268 cmd.max_acceleration= 0;
00269
00270 pr2_msgs::SetLaserTrajCmd laser_srv_cmd;
00271 laser_srv_cmd.request.command = cmd;
00272
00273 laser_controller_sc_.call(laser_srv_cmd);
00274
00275
00276 interval_start_ = laser_srv_cmd.response.start_time + cmd.time_from_start[1];
00277 interval_end_ = laser_srv_cmd.response.start_time + cmd.time_from_start[2];
00278
00279
00280 assert(state_ == SnapshotStates::IDLE);
00281 state_ = SnapshotStates::COLLECTING;
00282
00283 snapshot_feedback_.cloud.data.clear();
00284 snapshot_result_.cloud.data.clear();
00285 }
00286
00287 void Snapshotter::cancelCallback(SnapshotActionServer::GoalHandle gh)
00288 {
00289 boost::mutex::scoped_lock lock(state_mutex_);
00290
00291
00292 if (current_gh_ != gh)
00293 {
00294 ROS_DEBUG("Got a cancel request for some other goal. Ignoring it");
00295 return;
00296 }
00297 current_gh_.setCanceled();
00298 state_ = SnapshotStates::IDLE;
00299 }
00300
00301
00302
00303
00304
00305
00306
00307
00308
00309
00310
00311 int main(int argc, char** argv)
00312 {
00314
00315
00316
00317
00318
00319
00320
00321
00322
00323
00324
00325
00326
00327 ros::init(argc, argv, "laser_snapshotter");
00328 Snapshotter snapshotter;
00329 ros::spin();
00330 }