Public Member Functions | Private Member Functions | Private Attributes
depth_sensor_pose::DepthSensorPoseNode Class Reference

#include <depth_sensor_pose_node.h>

List of all members.

Public Member Functions

 DepthSensorPoseNode (ros::NodeHandle &n, ros::NodeHandle &pnh)
float getNodeRate ()
 getNodeRate gets rate of data processing loop in node.
void setNodeRate (const float rate)
 setNodeRate sets rate of processing data loop in node.
 ~DepthSensorPoseNode ()

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 (depth_sensor_pose::DepthSensorPoseConfig &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.
depth_sensor_pose::DepthSensorPose estimator_
 Object which contain estimation methods.
image_transport::ImageTransport it_
 Subscribes to synchronized Image CameraInfo pairs.
float node_rate_hz_
 Node loop frequency in Hz.
ros::NodeHandle pnh_
 Private node handler.
image_transport::Publisher pub_
 Publisher for image_transport.
ros::Publisher pub_angle_
 Publisher for estimated sensor tilt angle.
ros::Publisher pub_height_
 Publisher for estimated sensor height.
dynamic_reconfigure::Server
< depth_sensor_pose::DepthSensorPoseConfig > 
srv_
 Dynamic reconfigure server.
image_transport::CameraSubscriber sub_
 Subscriber for image_transport.

Detailed Description

Definition at line 57 of file depth_sensor_pose_node.h.


Constructor & Destructor Documentation

Definition at line 44 of file depth_sensor_pose_node.cpp.

Definition at line 69 of file depth_sensor_pose_node.cpp.


Member Function Documentation

void DepthSensorPoseNode::connectCb ( ) [private]

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:
pubPublisher which subscribers are checked.

Definition at line 119 of file depth_sensor_pose_node.cpp.

void DepthSensorPoseNode::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 runs sensor mount parameters estimation algorithms

Parameters:
depth_msgDepth image provided by image_transport.
info_msgCameraInfo provided by image_transport.

Definition at line 90 of file depth_sensor_pose_node.cpp.

disconnectCb is called when a subscriber stop subscribing

When no one subscribers subscribe topics, then it stop to subscribe depth image.

Parameters:
pubPublisher which subscribers are checked.

Definition at line 132 of file depth_sensor_pose_node.cpp.

getNodeRate gets rate of data processing loop in node.

Returns:
Returns data processing loop rate in Hz.

Definition at line 84 of file depth_sensor_pose_node.cpp.

void DepthSensorPoseNode::reconfigureCb ( depth_sensor_pose::DepthSensorPoseConfig &  config,
uint32_t  level 
) [private]

reconfigureCb is dynamic reconfigure callback

Callback is necessary to set ROS parameters with dynamic reconfigure server.

Parameters:
configDynamic Reconfigure object.
levelDynamic Reconfigure level.

Definition at line 144 of file depth_sensor_pose_node.cpp.

void DepthSensorPoseNode::setNodeRate ( const float  rate)

setNodeRate sets rate of processing data loop in node.

Parameters:
rateFrequency of data processing loop in Hz.

Definition at line 75 of file depth_sensor_pose_node.cpp.


Member Data Documentation

Prevents the connectCb and disconnectCb from being called until everything is initialized.

Definition at line 133 of file depth_sensor_pose_node.h.

Object which contain estimation methods.

Definition at line 130 of file depth_sensor_pose_node.h.

Subscribes to synchronized Image CameraInfo pairs.

Definition at line 119 of file depth_sensor_pose_node.h.

Node loop frequency in Hz.

Definition at line 116 of file depth_sensor_pose_node.h.

Private node handler.

Definition at line 117 of file depth_sensor_pose_node.h.

Publisher for image_transport.

Definition at line 124 of file depth_sensor_pose_node.h.

Publisher for estimated sensor tilt angle.

Definition at line 123 of file depth_sensor_pose_node.h.

Publisher for estimated sensor height.

Definition at line 122 of file depth_sensor_pose_node.h.

dynamic_reconfigure::Server<depth_sensor_pose::DepthSensorPoseConfig> depth_sensor_pose::DepthSensorPoseNode::srv_ [private]

Dynamic reconfigure server.

Definition at line 127 of file depth_sensor_pose_node.h.

Subscriber for image_transport.

Definition at line 120 of file depth_sensor_pose_node.h.


The documentation for this class was generated from the following files:


depth_sensor_pose
Author(s): Michal Drwiega
autogenerated on Thu Jun 6 2019 22:10:50