#include <cliff_detector_node.h>
Public Member Functions | |
| CliffDetectorNode (ros::NodeHandle &n, ros::NodeHandle &pnh) | |
| unsigned int | getNodeRate () |
| getNodeRate gets rate of data processing loop in node. | |
| void | setNodeRate (const unsigned int rate) |
| setNodeRate sets rate of processing data loop in node. | |
| ~CliffDetectorNode () | |
Private Member Functions | |
| void | connectCb () |
| connectCb is callback which is called when new subscriber connected. | |
| 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 | |
| void | disconnectCb () |
| disconnectCb is called when a subscriber stop subscribing | |
| void | reconfigureCb (cliff_detector::CliffDetectorConfig &config, uint32_t level) |
| reconfigureCb is dynamic reconfigure callback | |
Private Attributes | |
| boost::mutex | connection_mutex_ |
| Prevents the connectCb and disconnectCb from being called until everything is initialized. | |
| cliff_detector::CliffDetector | detector_ |
| Contains cliff detection method implementation. | |
| image_transport::ImageTransport | it_ |
| Subscribes to synchronized Image CameraInfo pairs. | |
| unsigned int | node_rate_hz_ |
| ros::NodeHandle | pnh_ |
| Private node handler used to generate the transport hints in the connectCb. | |
| image_transport::Publisher | pub_ |
| Publisher for image_transport. | |
| ros::Publisher | pub_points_ |
| Publisher for publishing messages with stairs points. | |
| dynamic_reconfigure::Server < cliff_detector::CliffDetectorConfig > | reconf_srv_ |
| Dynamic reconfigure server. | |
| image_transport::CameraSubscriber | sub_ |
| Subscriber for image_transport. | |
Definition at line 59 of file cliff_detector_node.h.
| CliffDetectorNode::CliffDetectorNode | ( | ros::NodeHandle & | n, |
| ros::NodeHandle & | pnh | ||
| ) |
Definition at line 42 of file cliff_detector_node.cpp.
Definition at line 60 of file cliff_detector_node.cpp.
| void CliffDetectorNode::connectCb | ( | ) | [private] |
connectCb is callback which is called when new subscriber connected.
It allow to subscribe depth image and publish laserscan message only when is laserscan subscriber appear.
| pub | Publisher which subscribers are checked. |
Definition at line 103 of file cliff_detector_node.cpp.
| void CliffDetectorNode::depthCb | ( | const sensor_msgs::ImageConstPtr & | depth_msg, |
| const sensor_msgs::CameraInfoConstPtr & | info_msg | ||
| ) | [private] |
depthCb is callback which is called when new depth image appear
Callback for depth image and camera info. It converts depth image to laserscan and publishes it at the end.
| depth_msg | Depth image provided by image_transport. |
| info_msg | CameraInfo provided by image_transport. |
Definition at line 81 of file cliff_detector_node.cpp.
| void CliffDetectorNode::disconnectCb | ( | ) | [private] |
disconnectCb is called when a subscriber stop subscribing
When no one subscribers subscribe laserscan topic, then it stop to subscribe depth image.
| pub | Publisher which subscribers are checked. |
Definition at line 115 of file cliff_detector_node.cpp.
| unsigned int CliffDetectorNode::getNodeRate | ( | ) |
getNodeRate gets rate of data processing loop in node.
Definition at line 75 of file cliff_detector_node.cpp.
| void CliffDetectorNode::reconfigureCb | ( | cliff_detector::CliffDetectorConfig & | config, |
| uint32_t | level | ||
| ) | [private] |
reconfigureCb is dynamic reconfigure callback
Callback is necessary to set ROS parameters with dynamic reconfigure server.
| config | Dynamic Reconfigure object. |
| level | Dynamic Reconfigure level. |
Definition at line 126 of file cliff_detector_node.cpp.
| void CliffDetectorNode::setNodeRate | ( | const unsigned int | rate | ) |
setNodeRate sets rate of processing data loop in node.
| rate | Frequency of data processing loop in Hz. |
Definition at line 66 of file cliff_detector_node.cpp.
boost::mutex cliff_detector::CliffDetectorNode::connection_mutex_ [private] |
Prevents the connectCb and disconnectCb from being called until everything is initialized.
Definition at line 134 of file cliff_detector_node.h.
Contains cliff detection method implementation.
Definition at line 132 of file cliff_detector_node.h.
Subscribes to synchronized Image CameraInfo pairs.
Definition at line 122 of file cliff_detector_node.h.
unsigned int cliff_detector::CliffDetectorNode::node_rate_hz_ [private] |
Definition at line 118 of file cliff_detector_node.h.
Private node handler used to generate the transport hints in the connectCb.
Definition at line 120 of file cliff_detector_node.h.
Publisher for image_transport.
Definition at line 126 of file cliff_detector_node.h.
Publisher for publishing messages with stairs points.
Definition at line 128 of file cliff_detector_node.h.
dynamic_reconfigure::Server<cliff_detector::CliffDetectorConfig> cliff_detector::CliffDetectorNode::reconf_srv_ [private] |
Dynamic reconfigure server.
Definition at line 130 of file cliff_detector_node.h.
Subscriber for image_transport.
Definition at line 124 of file cliff_detector_node.h.