#include <sensor_message_gateway_node.h>
Public Member Functions | |
SensorMessageGatewayNode (ros::NodeHandle nh) | |
~SensorMessageGatewayNode (void) | |
Destructor. | |
Protected Member Functions | |
void | imageCallback (const sensor_msgs::ImageConstPtr &color_image_msg) |
void | pointcloudCallback (const sensor_msgs::PointCloud2::ConstPtr &pointcloud) |
Callback for incoming point clouds. | |
void | reconfigureCallback (cob_people_detection::sensor_message_gatewayConfig &config, uint32_t level) |
Protected Attributes | |
image_transport::Publisher | color_image_pub_ |
Color camera image output topic. | |
image_transport::SubscriberFilter | color_image_sub_ |
Color camera image input topic. | |
bool | display_timing_ |
displays runtimes | |
sensor_msgs::Image | image_buffer_ |
boost::mutex | image_buffer_mutex_ |
secures the access to the image buffer | |
image_transport::ImageTransport * | it_ |
ros::Time | last_publishing_time_image_ |
time of the last publishing activity | |
ros::Time | last_publishing_time_pcl_ |
time of the last publishing activity | |
ros::NodeHandle | node_handle_ |
ros::Publisher | pointcloud_pub_ |
publisher for the colored point cloud | |
ros::Subscriber | pointcloud_sub_ |
subscribes to a colored point cloud | |
dynamic_reconfigure::Server < cob_people_detection::sensor_message_gatewayConfig > | reconfigure_server_ |
ros::Duration | target_publishing_delay_ |
computed from target_publishing_rate_ | |
double | target_publishing_rate_ |
rate at which the input messages are published (in Hz) |
Definition at line 87 of file sensor_message_gateway_node.h.
Constructor
nh | ROS node handle |
Definition at line 72 of file sensor_message_gateway_node.cpp.
Destructor.
Definition at line 109 of file sensor_message_gateway_node.cpp.
void cob_people_detection::SensorMessageGatewayNode::imageCallback | ( | const sensor_msgs::ImageConstPtr & | color_image_msg | ) | [protected] |
Definition at line 135 of file sensor_message_gateway_node.cpp.
void cob_people_detection::SensorMessageGatewayNode::pointcloudCallback | ( | const sensor_msgs::PointCloud2::ConstPtr & | pointcloud | ) | [protected] |
Callback for incoming point clouds.
Definition at line 115 of file sensor_message_gateway_node.cpp.
void cob_people_detection::SensorMessageGatewayNode::reconfigureCallback | ( | cob_people_detection::sensor_message_gatewayConfig & | config, |
uint32_t | level | ||
) | [protected] |
Definition at line 152 of file sensor_message_gateway_node.cpp.
image_transport::Publisher cob_people_detection::SensorMessageGatewayNode::color_image_pub_ [protected] |
Color camera image output topic.
Definition at line 114 of file sensor_message_gateway_node.h.
image_transport::SubscriberFilter cob_people_detection::SensorMessageGatewayNode::color_image_sub_ [protected] |
Color camera image input topic.
Definition at line 113 of file sensor_message_gateway_node.h.
bool cob_people_detection::SensorMessageGatewayNode::display_timing_ [protected] |
displays runtimes
Definition at line 128 of file sensor_message_gateway_node.h.
sensor_msgs::Image cob_people_detection::SensorMessageGatewayNode::image_buffer_ [protected] |
Definition at line 119 of file sensor_message_gateway_node.h.
boost::mutex cob_people_detection::SensorMessageGatewayNode::image_buffer_mutex_ [protected] |
secures the access to the image buffer
Definition at line 122 of file sensor_message_gateway_node.h.
Definition at line 112 of file sensor_message_gateway_node.h.
time of the last publishing activity
Definition at line 127 of file sensor_message_gateway_node.h.
time of the last publishing activity
Definition at line 126 of file sensor_message_gateway_node.h.
Definition at line 107 of file sensor_message_gateway_node.h.
publisher for the colored point cloud
Definition at line 110 of file sensor_message_gateway_node.h.
subscribes to a colored point cloud
Definition at line 109 of file sensor_message_gateway_node.h.
dynamic_reconfigure::Server<cob_people_detection::sensor_message_gatewayConfig> cob_people_detection::SensorMessageGatewayNode::reconfigure_server_ [protected] |
Definition at line 105 of file sensor_message_gateway_node.h.
computed from target_publishing_rate_
Definition at line 116 of file sensor_message_gateway_node.h.
double cob_people_detection::SensorMessageGatewayNode::target_publishing_rate_ [protected] |
rate at which the input messages are published (in Hz)
Definition at line 125 of file sensor_message_gateway_node.h.