34 #include <pr2_tilt_laser_interface/GetSnapshotAction.h> 37 #include <pr2_msgs/SetLaserTrajCmd.h> 40 #include <sensor_msgs/LaserScan.h> 48 #include <pcl/io/io.h> 50 void appendCloud(sensor_msgs::PointCloud2& dest,
const sensor_msgs::PointCloud2& src)
55 size_t start = dest.data.size ();
63 dest.data.resize (start + src.data.size ());
64 memcpy (&dest.data[start], &src.data[0], src.data.size ());
68 float time_offset = src.header.stamp.toSec () - dest.header.stamp.toSec ();
70 for (
size_t i = 0; i < src.width * src.height; ++i)
72 time_ptr = (
float*) &dest.data[start + i * src.point_step + time_index];
73 *time_ptr += time_offset;
96 void startScan(
double move_to_start_wait_time=1.0);
98 void scanCallback(
const sensor_msgs::LaserScanConstPtr& scan);
124 boost::scoped_ptr<tf::MessageFilter<sensor_msgs::LaserScan> >
tf_filter_;
129 as_(nh_,
"get_laser_snapshot", false),
143 ROS_FATAL(
"Need to set parameter ~fixed_frame");
169 ROS_DEBUG(
"Waiting to get to the start of the interval");
177 sensor_msgs::PointCloud2 cur_cloud_tf;
179 if (!
goal_.hi_fidelity)
181 sensor_msgs::PointCloud2 cur_cloud;
195 ROS_DEBUG (
"Bundling everything up and publishing cloud with %u points", cloud.width * cloud.width);
199 if (
goal_.continuous)
203 std::swap(
goal_.start_angle,
goal_.end_angle);
214 ROS_ERROR(
"In an unknown state. This is a programming error");
243 pr2_msgs::LaserTrajCmd
cmd;
245 cmd.profile =
"linear";
246 cmd.position.resize(4);
247 cmd.position[0] =
goal_.start_angle;
248 cmd.position[1] =
goal_.start_angle;
249 cmd.position[2] =
goal_.end_angle;
250 cmd.position[3] = (
goal_.continuous ?
goal_.end_angle :
goal_.start_angle);
252 if (
goal_.speed==0.0)
254 ROS_ERROR(
"Scan speed is set to zero -> aborting!\n");
259 if (scan_duration.
toSec() < 0.0)
260 scan_duration = -scan_duration;
263 cmd.time_from_start.resize(4);
265 cmd.time_from_start[1] = wait_time;
266 cmd.time_from_start[2] = wait_time + scan_duration;
267 cmd.time_from_start[3] = wait_time + scan_duration + scan_duration;
268 cmd.max_velocity = 0;
269 cmd.max_acceleration= 0;
271 pr2_msgs::SetLaserTrajCmd laser_srv_cmd;
272 laser_srv_cmd.request.command = cmd;
277 interval_start_ = laser_srv_cmd.response.start_time + cmd.time_from_start[1];
278 interval_end_ = laser_srv_cmd.response.start_time + cmd.time_from_start[2];
295 ROS_DEBUG(
"Got a cancel request for some other goal. Ignoring it");
312 int main(
int argc,
char** argv)
328 ros::init(argc, argv,
"laser_snapshotter");
void projectLaser(const sensor_msgs::LaserScan &scan_in, sensor_msgs::PointCloud &cloud_out, double range_cutoff=-1.0, int channel_options=channel_option::Default)
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
void publishFeedback(const Feedback &feedback)
message_filters::Subscriber< sensor_msgs::LaserScan > scan_sub_
void cancelCallback(SnapshotActionServer::GoalHandle gh)
ServerGoalHandle< GetSnapshotAction > GoalHandle
boost::mutex state_mutex_
int main(int argc, char **argv)
laser_geometry::LaserProjection lg_
ros::Time interval_start_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
boost::shared_ptr< const Goal > getGoal() const
GetSnapshotResult snapshot_result_
void setCanceled(const Result &result=Result(), const std::string &text=std::string(""))
ROSCPP_DECL void spin(Spinner &spinner)
SnapshotStates::SnapshotState SnapshotState
void setAccepted(const std::string &text=std::string(""))
void registerGoalCallback(boost::function< void(GoalHandle)> cb)
void startScan(double move_to_start_wait_time=1.0)
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
void goalCallback(SnapshotActionServer::GoalHandle gh)
void scanCallback(const sensor_msgs::LaserScanConstPtr &scan)
SnapshotActionServer::GoalHandle current_gh_
void appendCloud(sensor_msgs::PointCloud2 &dest, const sensor_msgs::PointCloud2 &src)
void registerCancelCallback(boost::function< void(GoalHandle)> cb)
ros::ServiceClient laser_controller_sc_
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
void transformPointCloud(const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const tf::Transform &transform)
void transformLaserScanToPointCloud(const std::string &target_frame, const sensor_msgs::LaserScan &scan_in, sensor_msgs::PointCloud &cloud_out, tf::Transformer &tf, double range_cutoff, int channel_options=channel_option::Default)
boost::scoped_ptr< tf::MessageFilter< sensor_msgs::LaserScan > > tf_filter_
actionlib::ActionServer< GetSnapshotAction > SnapshotActionServer
int getFieldIndex(const sensor_msgs::PointCloud2 &cloud, const std::string &field_name)
GetSnapshotFeedback snapshot_feedback_
tf::TransformListener tf_