#include <depth_sensor_pose_node.h>
|
void | connectCallback () |
| connectCb is callback which is called when new subscriber connected. More...
|
|
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 More...
|
|
void | disconnectCallback () |
| disconnectCb is called when a subscriber stop subscribing More...
|
|
void | reconfigureCallback (depth_sensor_pose::DepthSensorPoseConfig &config, uint32_t level) |
| reconfigureCb is dynamic reconfigure callback More...
|
|
Definition at line 21 of file depth_sensor_pose_node.h.
DepthSensorPoseNode::~DepthSensorPoseNode |
( |
| ) |
|
void DepthSensorPoseNode::connectCallback |
( |
| ) |
|
|
protected |
connectCb is callback which is called when new subscriber connected.
It allow to subscribe depth image and publish prepared message only when is subscriber appear.
- Parameters
-
pub | Publisher which subscribers are checked. |
Definition at line 77 of file depth_sensor_pose_node.cpp.
void DepthSensorPoseNode::depthCallback |
( |
const sensor_msgs::ImageConstPtr & |
depth_msg, |
|
|
const sensor_msgs::CameraInfoConstPtr & |
info_msg |
|
) |
| |
|
protected |
depthCb is callback which is called when new depth image appear
Callback for depth image and camera info. It runs sensor mount parameters estimation algorithms
- Parameters
-
Definition at line 50 of file depth_sensor_pose_node.cpp.
void DepthSensorPoseNode::disconnectCallback |
( |
| ) |
|
|
protected |
disconnectCb is called when a subscriber stop subscribing
When no one subscribers subscribe topics, then it stop to subscribe depth image.
- Parameters
-
pub | Publisher which subscribers are checked. |
Definition at line 87 of file depth_sensor_pose_node.cpp.
float DepthSensorPoseNode::getNodeRate |
( |
| ) |
|
getNodeRate gets rate of data processing loop in node.
- Returns
- Returns data processing loop rate in Hz.
Definition at line 46 of file depth_sensor_pose_node.cpp.
void DepthSensorPoseNode::reconfigureCallback |
( |
depth_sensor_pose::DepthSensorPoseConfig & |
config, |
|
|
uint32_t |
level |
|
) |
| |
|
protected |
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 96 of file depth_sensor_pose_node.cpp.
void DepthSensorPoseNode::setNodeRate |
( |
const float |
rate | ) |
|
setNodeRate sets rate of processing data loop in node.
- Parameters
-
rate | Frequency of data processing loop in Hz. |
Definition at line 38 of file depth_sensor_pose_node.cpp.
std::mutex depth_sensor_pose::DepthSensorPoseNode::connection_mutex_ |
|
private |
Prevents the connectCb and disconnectCb from being called until everything is initialized.
Definition at line 102 of file depth_sensor_pose_node.h.
dynamic_reconfigure::Server<depth_sensor_pose::DepthSensorPoseConfig> depth_sensor_pose::DepthSensorPoseNode::dyn_rec_srv_ |
|
private |
float depth_sensor_pose::DepthSensorPoseNode::node_rate_hz_ {1} |
|
private |
The documentation for this class was generated from the following files: