Public Member Functions | Private Member Functions | Private Attributes | List of all members
cliff_detector::CliffDetectorNode Class Reference

#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. More...
 
void setNodeRate (const unsigned int rate)
 setNodeRate sets rate of processing data loop in node. More...
 
 ~CliffDetectorNode ()
 

Private Member Functions

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...
 

Private Attributes

boost::mutex connection_mutex_
 Prevents the connectCb and disconnectCb from being called until everything is initialized. More...
 
cliff_detector::CliffDetector detector_
 Contains cliff detection method implementation. More...
 
image_transport::ImageTransport it_
 Subscribes to synchronized Image CameraInfo pairs. More...
 
unsigned int node_rate_hz_
 
ros::NodeHandle pnh_
 Private node handler used to generate the transport hints in the connectCb. More...
 
image_transport::Publisher pub_
 Publisher for image_transport. More...
 
ros::Publisher pub_points_
 Publisher for publishing messages with stairs points. More...
 
dynamic_reconfigure::Server< cliff_detector::CliffDetectorConfig > reconf_srv_
 Dynamic reconfigure server. More...
 
image_transport::CameraSubscriber sub_
 Subscriber for image_transport. More...
 

Detailed Description

Definition at line 22 of file cliff_detector_node.h.

Constructor & Destructor Documentation

cliff_detector::CliffDetectorNode::CliffDetectorNode ( ros::NodeHandle n,
ros::NodeHandle pnh 
)

Definition at line 5 of file cliff_detector_node.cpp.

cliff_detector::CliffDetectorNode::~CliffDetectorNode ( )

Definition at line 21 of file cliff_detector_node.cpp.

Member Function Documentation

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
pubPublisher 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
depth_msgDepth image provided by image_transport.
info_msgCameraInfo provided by image_transport.

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
pubPublisher 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
configDynamic Reconfigure object.
levelDynamic 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
rateFrequency of data processing loop in Hz.

Definition at line 25 of file cliff_detector_node.cpp.

Member Data Documentation

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.

cliff_detector::CliffDetector cliff_detector::CliffDetectorNode::detector_
private

Contains cliff detection method implementation.

Definition at line 94 of file cliff_detector_node.h.

image_transport::ImageTransport cliff_detector::CliffDetectorNode::it_
private

Subscribes to synchronized Image CameraInfo pairs.

Definition at line 84 of file cliff_detector_node.h.

unsigned int cliff_detector::CliffDetectorNode::node_rate_hz_
private

Definition at line 80 of file cliff_detector_node.h.

ros::NodeHandle cliff_detector::CliffDetectorNode::pnh_
private

Private node handler used to generate the transport hints in the connectCb.

Definition at line 82 of file cliff_detector_node.h.

image_transport::Publisher cliff_detector::CliffDetectorNode::pub_
private

Publisher for image_transport.

Definition at line 88 of file cliff_detector_node.h.

ros::Publisher cliff_detector::CliffDetectorNode::pub_points_
private

Publisher for publishing messages with stairs points.

Definition at line 90 of file cliff_detector_node.h.

dynamic_reconfigure::Server<cliff_detector::CliffDetectorConfig> cliff_detector::CliffDetectorNode::reconf_srv_
private

Dynamic reconfigure server.

Definition at line 92 of file cliff_detector_node.h.

image_transport::CameraSubscriber cliff_detector::CliffDetectorNode::sub_
private

Subscriber for image_transport.

Definition at line 86 of file cliff_detector_node.h.


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


cliff_detector
Author(s): Michal Drwiega (http://www.mdrwiega.com)
autogenerated on Wed May 5 2021 02:56:04