cliff_detector_node.cpp
Go to the documentation of this file.
00001 /******************************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  * Copyright (c) 2015, Michal Drwiega (drwiega.michal@gmail.com)
00005  * All rights reserved.
00006  *
00007  * Redistribution and use in source and binary forms, with or without
00008  * modification, are permitted provided that the following conditions are met:
00009  *     1. Redistributions of source code must retain the above copyright
00010  *        notice, this list of conditions and the following disclaimer.
00011  *     2. Redistributions in binary form must reproduce the above copyright
00012  *        notice, this list of conditions and the following disclaimer in the
00013  *        documentation and/or other materials provided with the distribution.
00014  *     3. Neither the name of the copyright holder nor the names of its
00015  *        contributors may be used to endorse or promote products derived
00016  *        from this software without specific prior written permission.
00017  *
00018  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00019  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00020  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
00021  * A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
00022  * HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
00023  * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED
00024  * TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
00025  * PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
00026  * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
00027  * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00028  * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
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   // Set callback for dynamic reconfigure server
00048   reconf_srv_.setCallback(boost::bind(&CliffDetectorNode::reconfigureCb, this, _1, _2));
00049 
00050   // New depth image publisher
00051   pub_ = it_.advertise("cliff_detector/depth", 1,
00052                        boost::bind(&CliffDetectorNode::connectCb, this),
00053                        boost::bind(&CliffDetectorNode::disconnectCb, this));
00054 
00055   // Publisher for stairs points msg
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     // Run cliff detector based on depth image
00087     detector_.detectCliff(depth_msg, info_msg);
00088 
00089     // Publish stairs points msg
00090     pub_points_.publish(detector_.stairs_points_msg_);
00091 
00092     // Publishes new depth image with added cliff
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 }


cliff_detector
Author(s): Michal Drwiega
autogenerated on Thu Jun 6 2019 22:10:46