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 <cliff_detector/cliff_detector_node.h>
00038
00039 using namespace cliff_detector;
00040
00041
00042 CliffDetectorNode::CliffDetectorNode( ros::NodeHandle& n, ros::NodeHandle& pnh ):
00043 node_rate_hz_(2), pnh_(pnh), it_(n), reconf_srv_(pnh)
00044 {
00045 boost::mutex::scoped_lock lock(connection_mutex_);
00046
00047
00048 reconf_srv_.setCallback(boost::bind(&CliffDetectorNode::reconfigureCb, this, _1, _2));
00049
00050
00051 pub_ = it_.advertise("cliff_detector/depth", 1,
00052 boost::bind(&CliffDetectorNode::connectCb, this),
00053 boost::bind(&CliffDetectorNode::disconnectCb, this));
00054
00055
00056 pub_points_ = n.advertise<depth_nav_msgs::Point32List>("cliff_detector/points", 2);
00057 }
00058
00059
00060 CliffDetectorNode::~CliffDetectorNode()
00061 {
00062 sub_.shutdown();
00063 }
00064
00065
00066 void CliffDetectorNode::setNodeRate(const unsigned int rate)
00067 {
00068 if (rate <= 30)
00069 node_rate_hz_ = rate;
00070 else
00071 node_rate_hz_ = 30;
00072 }
00073
00074
00075 unsigned int CliffDetectorNode::getNodeRate()
00076 {
00077 return node_rate_hz_;
00078 }
00079
00080
00081 void CliffDetectorNode::depthCb(const sensor_msgs::ImageConstPtr& depth_msg,
00082 const sensor_msgs::CameraInfoConstPtr& info_msg)
00083 {
00084 try
00085 {
00086
00087 detector_.detectCliff(depth_msg, info_msg);
00088
00089
00090 pub_points_.publish(detector_.stairs_points_msg_);
00091
00092
00093 if (detector_.getPublishDepthEnable())
00094 pub_.publish(detector_.new_depth_msg_);
00095 }
00096 catch (std::runtime_error& e)
00097 {
00098 ROS_ERROR_THROTTLE(1.0, "Could not perform stairs detection: %s", e.what());
00099 }
00100 }
00101
00102
00103 void CliffDetectorNode::connectCb()
00104 {
00105 boost::mutex::scoped_lock lock(connection_mutex_);
00106 if (!sub_ && pub_.getNumSubscribers() > 0)
00107 {
00108 ROS_DEBUG("Connecting to depth topic.");
00109 image_transport::TransportHints hints("raw", ros::TransportHints(), pnh_);
00110 sub_ = it_.subscribeCamera("image", 1, &CliffDetectorNode::depthCb, this, hints);
00111 }
00112 }
00113
00114
00115 void CliffDetectorNode::disconnectCb()
00116 {
00117 boost::mutex::scoped_lock lock(connection_mutex_);
00118 if (pub_.getNumSubscribers() == 0)
00119 {
00120 ROS_DEBUG("Unsubscribing from depth topic.");
00121 sub_.shutdown();
00122 }
00123 }
00124
00125
00126 void CliffDetectorNode::reconfigureCb(
00127 cliff_detector::CliffDetectorConfig& config, uint32_t level)
00128 {
00129 node_rate_hz_ = (unsigned int) config.rate;
00130
00131 detector_.setRangeLimits(config.range_min, config.range_max);
00132 detector_.setSensorMountHeight(config.sensor_mount_height);
00133 detector_.setSensorTiltAngle(config.sensor_tilt_angle);
00134 detector_.setPublishDepthEnable(config.publish_depth);
00135 detector_.setCamModelUpdate(config.cam_model_update);
00136
00137 detector_.setUsedDepthHeight((unsigned int)config.used_depth_height);
00138 detector_.setBlockSize(config.block_size);
00139 detector_.setBlockPointsThresh(config.block_points_thresh);
00140 detector_.setDepthImgStepRow(config.depth_img_step_row);
00141 detector_.setDepthImgStepCol(config.depth_img_step_col);
00142 detector_.setGroundMargin(config.ground_margin);
00143
00144 detector_.setParametersConfigurated(false);
00145 }