depth_sensor_pose_node.cpp
Go to the documentation of this file.
1 #include <functional>
2 
4 
5 constexpr int MAX_NODE_RATE = 30;
6 
7 using namespace depth_sensor_pose;
8 
10  : pnh_(pnh), it_(pnh), dyn_rec_srv_(pnh)
11 {
12  std::lock_guard<std::mutex> lock(connection_mutex_);
13 
14  // Dynamic reconfigure server callback
15  dyn_rec_srv_.setCallback(
16  boost::bind(&DepthSensorPoseNode::reconfigureCallback, this, _1, _2));
17 
18  // Lazy subscription implementation
19  // Tilt angle and height publisher
20  pub_height_ = pnh_.advertise<std_msgs::Float64>("height", 2,
21  std::bind(&DepthSensorPoseNode::connectCallback, this),
22  std::bind(&DepthSensorPoseNode::disconnectCallback, this));
23 
24  pub_angle_ = pnh_.advertise<std_msgs::Float64>("tilt_angle", 2,
25  std::bind(&DepthSensorPoseNode::connectCallback, this),
26  std::bind(&DepthSensorPoseNode::disconnectCallback, this));
27 
28  // New depth image publisher
29  pub_ = it_.advertise("debug_image", 1,
30  std::bind(&DepthSensorPoseNode::connectCallback, this),
31  std::bind(&DepthSensorPoseNode::disconnectCallback, this));
32 }
33 
35  sub_.shutdown();
36 }
37 
38 void DepthSensorPoseNode::setNodeRate(const float rate) {
39  if (rate <= MAX_NODE_RATE) {
40  node_rate_hz_ = rate;
41  }
42  else
44 }
45 
47  return node_rate_hz_;
48 }
49 
50 void DepthSensorPoseNode::depthCallback(const sensor_msgs::ImageConstPtr& depth_msg,
51  const sensor_msgs::CameraInfoConstPtr& info_msg) {
52  try {
53  // Estimation of parameters -- sensor pose
54  estimator_.estimateParams(depth_msg, info_msg);
55 
56  std_msgs::Float64 height, tilt_angle;
57  height.data = estimator_.getSensorMountHeight();
58  tilt_angle.data = estimator_.getSensorTiltAngle();
59 
60  pub_height_.publish(height);
61  pub_angle_.publish(tilt_angle);
62  ROS_DEBUG("Publish sensor height (%.2f) and tilt angle (%.2f)", height.data, tilt_angle.data);
63 
64  // Publish debug image
66  auto dbg_image = estimator_.getDbgImage();
67  if (dbg_image != nullptr) {
68  pub_.publish(dbg_image);
69  }
70  }
71  }
72  catch (std::runtime_error& e) {
73  ROS_ERROR_THROTTLE(1.0, "Could not to run estimation procedure: %s", e.what());
74  }
75 }
76 
78  std::lock_guard<std::mutex> lock(connection_mutex_);
79  if (sub_ == nullptr && (pub_height_.getNumSubscribers() > 0 || pub_angle_.getNumSubscribers() > 0
80  || pub_.getNumSubscribers() > 0)) {
81  ROS_DEBUG("Connecting to depth topic.");
83  sub_ = it_.subscribeCamera("image", 1, &DepthSensorPoseNode::depthCallback, this, hints);
84  }
85 }
86 
88  std::lock_guard<std::mutex> lock(connection_mutex_);
90  && pub_.getNumSubscribers() == 0) {
91  ROS_DEBUG("Unsubscribing from depth topic.");
92  sub_.shutdown();
93  }
94 }
95 
96 void DepthSensorPoseNode::reconfigureCallback(depth_sensor_pose::DepthSensorPoseConfig& config,
97  [[maybe_unused]] uint32_t level) {
98  node_rate_hz_ = static_cast<float>(config.rate);
99 
100  estimator_.setRangeLimits(config.range_min, config.range_max);
101  estimator_.setSensorMountHeightMin(config.mount_height_min);
102  estimator_.setSensorMountHeightMax(config.mount_height_max);
103  estimator_.setSensorTiltAngleMin(config.tilt_angle_min);
104  estimator_.setSensorTiltAngleMax(config.tilt_angle_max);
105 
106  estimator_.setPublishDepthEnable(config.publish_dbg_info);
107  estimator_.setCamModelUpdate(config.cam_model_update);
108  estimator_.setUsedDepthHeight((unsigned int)config.used_depth_height);
109  estimator_.setDepthImgStepRow(config.depth_img_step_row);
110  estimator_.setDepthImgStepCol(config.depth_img_step_col);
111 
112  estimator_.setRansacDistanceThresh(config.ransac_dist_thresh);
113  estimator_.setRansacMaxIter(config.ransac_max_iter);
114  estimator_.setGroundMaxPoints(config.ground_max_points);
115 
117 }
void depthCallback(const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
depthCb is callback which is called when new depth image appear
void publish(const boost::shared_ptr< M > &message) const
void setUsedDepthHeight(const unsigned height)
setUsedDepthHeight
CameraSubscriber subscribeCamera(const std::string &base_topic, uint32_t queue_size, const CameraSubscriber::Callback &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
void disconnectCallback()
disconnectCb is called when a subscriber stop subscribing
void setRansacMaxIter(const unsigned u)
image_transport::ImageTransport it_
Subscribes to synchronized Image CameraInfo pairs.
std::mutex connection_mutex_
Prevents the connectCb and disconnectCb from being called until everything is initialized.
void setRangeLimits(const float rmin, const float rmax)
void setReconfParamsUpdated(bool updated)
setReconfParamsUpdated
void reconfigureCallback(depth_sensor_pose::DepthSensorPoseConfig &config, uint32_t level)
reconfigureCb is dynamic reconfigure callback
image_transport::CameraSubscriber sub_
Subscriber for image_transport.
uint32_t getNumSubscribers() const
image_transport::Publisher pub_
Publisher for image_transport.
#define ROS_ERROR_THROTTLE(rate,...)
void publish(const sensor_msgs::Image &message) const
constexpr int MAX_NODE_RATE
sensor_msgs::ImageConstPtr getDbgImage() const
void estimateParams(const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
void setSensorMountHeightMin(const float height)
setSensorMountHeight sets the height of sensor mount (in meters) from ground
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
float getNodeRate()
getNodeRate gets rate of data processing loop in node.
void setDepthImgStepCol(const int step)
setDepthImgStepCol
depth_sensor_pose::DepthSensorPose estimator_
Object which contain estimation methods.
void connectCallback()
connectCb is callback which is called when new subscriber connected.
void setDepthImgStepRow(const int step)
setDepthImgStepRow
void setNodeRate(const float rate)
setNodeRate sets rate of processing data loop in node.
void setCamModelUpdate(const bool u)
setCamModelUpdate
ros::NodeHandle pnh_
Private node handler.
uint32_t getNumSubscribers() const
ros::Publisher pub_height_
Publisher for estimated sensor height.
void setGroundMaxPoints(const unsigned u)
ros::Publisher pub_angle_
Publisher for estimated sensor tilt angle.
void setRansacDistanceThresh(const float u)
void setSensorTiltAngleMax(const float angle)
setSensorTiltAngle sets the sensor tilt angle (in degrees)
void setSensorMountHeightMax(const float height)
setSensorMountHeight sets the height of sensor mount (in meters) from ground
dynamic_reconfigure::Server< depth_sensor_pose::DepthSensorPoseConfig > dyn_rec_srv_
Dynamic reconfigure server.
bool getPublishDepthEnable() const
getPublishDepthEnable
float node_rate_hz_
Node loop frequency in Hz.
void setSensorTiltAngleMin(const float angle)
setSensorTiltAngle sets the sensor tilt angle (in degrees)
void setPublishDepthEnable(const bool enable)
setPublishDepthEnable
#define ROS_DEBUG(...)


depth_sensor_pose
Author(s): Michal Drwiega (http://www.mdrwiega.com)
autogenerated on Wed May 5 2021 02:56:10