#include <cliff_detector_node.h>
|
| void | connectCb () |
| | connectCb is callback which is called when new subscriber connected. More...
|
| |
| 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 More...
|
| |
| void | disconnectCb () |
| | disconnectCb is called when a subscriber stop subscribing More...
|
| |
| void | reconfigureCb (cliff_detector::CliffDetectorConfig &config, uint32_t level) |
| | reconfigureCb is dynamic reconfigure callback More...
|
| |
Definition at line 22 of file cliff_detector_node.h.
| cliff_detector::CliffDetectorNode::~CliffDetectorNode |
( |
| ) |
|
| void cliff_detector::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.
- Parameters
-
| pub | Publisher which subscribers are checked. |
Definition at line 57 of file cliff_detector_node.cpp.
| void cliff_detector::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.
- Parameters
-
Definition at line 38 of file cliff_detector_node.cpp.
| void cliff_detector::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.
- Parameters
-
| pub | Publisher which subscribers are checked. |
Definition at line 66 of file cliff_detector_node.cpp.
| unsigned int cliff_detector::CliffDetectorNode::getNodeRate |
( |
| ) |
|
getNodeRate gets rate of data processing loop in node.
- Returns
- Returns data processing loop rate in Hz.
Definition at line 34 of file cliff_detector_node.cpp.
| void cliff_detector::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.
- Parameters
-
| config | Dynamic Reconfigure object. |
| level | Dynamic Reconfigure level. |
Definition at line 74 of file cliff_detector_node.cpp.
| void cliff_detector::CliffDetectorNode::setNodeRate |
( |
const unsigned int |
rate | ) |
|
setNodeRate sets rate of processing data loop in node.
- Parameters
-
| rate | Frequency of data processing loop in Hz. |
Definition at line 25 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 96 of file cliff_detector_node.h.
| unsigned int cliff_detector::CliffDetectorNode::node_rate_hz_ |
|
private |
Private node handler used to generate the transport hints in the connectCb.
Definition at line 82 of file cliff_detector_node.h.
| dynamic_reconfigure::Server<cliff_detector::CliffDetectorConfig> cliff_detector::CliffDetectorNode::reconf_srv_ |
|
private |
The documentation for this class was generated from the following files: