cliff_detector_node.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <ros/ros.h>
5 #include <boost/thread/mutex.hpp>
6 #include <opencv2/highgui/highgui.hpp>
7 #include <opencv2/imgproc/imgproc.hpp>
8 #include <cv_bridge/cv_bridge.h>
9 
10 #include <sensor_msgs/Image.h>
11 #include <std_msgs/Float64.h>
13 #include <depth_nav_msgs/Point32List.h>
14 
15 #include <dynamic_reconfigure/server.h>
16 #include <cliff_detector/CliffDetectorConfig.h>
17 
19 
20 namespace cliff_detector {
21 
23  public:
31  void setNodeRate(const unsigned int rate);
36  unsigned int getNodeRate();
37 
38  private: // Private methods
48  void depthCb( const sensor_msgs::ImageConstPtr& depth_msg,
49  const sensor_msgs::CameraInfoConstPtr& info_msg);
58  void connectCb();
66  void disconnectCb();
75  void reconfigureCb(cliff_detector::CliffDetectorConfig& config,
76  uint32_t level);
77 
78  private: // Private fields
79  // Node loop frequency in Hz
80  unsigned int node_rate_hz_;
92  dynamic_reconfigure::Server<cliff_detector::CliffDetectorConfig> reconf_srv_;
96  boost::mutex connection_mutex_;
97  };
98 
99 } // namespace cliff_detector
image_transport::ImageTransport it_
Subscribes to synchronized Image CameraInfo pairs.
ros::NodeHandle pnh_
Private node handler used to generate the transport hints in the connectCb.
boost::mutex connection_mutex_
Prevents the connectCb and disconnectCb from being called until everything is initialized.
image_transport::Publisher pub_
Publisher for image_transport.
image_transport::CameraSubscriber sub_
Subscriber for image_transport.
cliff_detector::CliffDetector detector_
Contains cliff detection method implementation.
void disconnectCb()
disconnectCb is called when a subscriber stop subscribing
unsigned int getNodeRate()
getNodeRate gets rate of data processing loop in node.
void reconfigureCb(cliff_detector::CliffDetectorConfig &config, uint32_t level)
reconfigureCb is dynamic reconfigure callback
ros::Publisher pub_points_
Publisher for publishing messages with stairs points.
void setNodeRate(const unsigned int rate)
setNodeRate sets rate of processing data loop in node.
void connectCb()
connectCb is callback which is called when new subscriber connected.
The CliffDetector class detect cliff based on depth image.
void depthCb(const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
depthCb is callback which is called when new depth image appear
CliffDetectorNode(ros::NodeHandle &n, ros::NodeHandle &pnh)
dynamic_reconfigure::Server< cliff_detector::CliffDetectorConfig > reconf_srv_
Dynamic reconfigure server.


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