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
00037 #include <laserscan_kinect/laserscan_kinect_node.h>
00038
00039 using namespace laserscan_kinect;
00040
00041
00042 LaserScanKinectNode::LaserScanKinectNode(ros::NodeHandle& n, ros::NodeHandle& pnh) :
00043 pnh_(pnh), it_(n), srv_(pnh)
00044 {
00045 boost::mutex::scoped_lock lock(connect_mutex_);
00046
00047
00048 srv_.setCallback(boost::bind(&LaserScanKinectNode::reconfigureCb, this, _1, _2));
00049
00050
00051 pub_ = n.advertise<sensor_msgs::LaserScan>("scan", 10,
00052 boost::bind(&LaserScanKinectNode::connectCb, this, _1),
00053 boost::bind(&LaserScanKinectNode::disconnectCb, this, _1));
00054 }
00055
00056
00057 LaserScanKinectNode::~LaserScanKinectNode()
00058 {
00059 sub_.shutdown();
00060 }
00061
00062
00063 void LaserScanKinectNode::depthCb(const sensor_msgs::ImageConstPtr& depth_msg,
00064 const sensor_msgs::CameraInfoConstPtr& info_msg)
00065 {
00066 try
00067 {
00068 sensor_msgs::LaserScanPtr laserscan_msg = converter_.prepareLaserScanMsg(depth_msg, info_msg);
00069 pub_.publish(laserscan_msg);
00070 }
00071 catch (std::runtime_error& e)
00072 {
00073 ROS_ERROR_THROTTLE(1.0, "Could not convert depth image to laserscan: %s", e.what());
00074 }
00075 }
00076
00077
00078 void LaserScanKinectNode::connectCb(const ros::SingleSubscriberPublisher& pub)
00079 {
00080 boost::mutex::scoped_lock lock(connect_mutex_);
00081 if (!sub_ && pub_.getNumSubscribers() > 0)
00082 {
00083 ROS_DEBUG("Connecting to depth topic.");
00084 image_transport::TransportHints hints("raw", ros::TransportHints(), pnh_);
00085 sub_ = it_.subscribeCamera("image", 10, &LaserScanKinectNode::depthCb, this, hints);
00086 }
00087 }
00088
00089
00090 void LaserScanKinectNode::disconnectCb(const ros::SingleSubscriberPublisher& pub)
00091 {
00092 boost::mutex::scoped_lock lock(connect_mutex_);
00093 if (pub_.getNumSubscribers() == 0)
00094 {
00095 ROS_DEBUG("Unsubscribing from depth topic.");
00096 sub_.shutdown();
00097 }
00098 }
00099
00100
00101 void LaserScanKinectNode::reconfigureCb(laserscan_kinect::LaserscanKinectConfig& config,
00102 uint32_t level)
00103 {
00104 converter_.setOutputFrame(config.output_frame_id);
00105 converter_.setRangeLimits(config.range_min, config.range_max);
00106 converter_.setScanHeight(config.scan_height);
00107 converter_.setDepthImgRowStep(config.depth_img_row_step);
00108 converter_.setCamModelUpdate(config.cam_model_update);
00109
00110 converter_.setSensorMountHeight(config.sensor_mount_height);
00111 converter_.setSensorTiltAngle(config.sensor_tilt_angle);
00112 converter_.setGroundRemove(config.ground_remove_en);
00113 converter_.setGroundMargin(config.ground_margin);
00114 converter_.setTiltCompensation(config.tilt_compensation_en);
00115
00116 converter_.setScanConfigurated(false);
00117 }
00118
00119
00120