Public Member Functions | Protected Member Functions | Protected Attributes
CoordinatorNode Class Reference

#include <coordinator_node.h>

List of all members.

Public Member Functions

 CoordinatorNode (ros::NodeHandle nh)
 ~CoordinatorNode ()

Protected Member Functions

void detectionsCallback (const cob_perception_msgs::DetectionArray::ConstPtr &detection_array)
void getDetectionsServerCallback (const cob_people_detection::getDetectionsGoalConstPtr &goal)
bool startRecognitionCallback (cob_people_detection::recognitionTrigger::Request &req, cob_people_detection::recognitionTrigger::Response &res)
bool stopRecognitionCallback (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)

Protected Attributes

boost::mutex active_action_mutex_
 mutex to avoid double call of an action
ros::Subscriber detection_sub_
 recieves messages of detections
GetDetectionsServerget_detections_server_
 Action server that handles requests for people detections.
cob_perception_msgs::DetectionArray last_detection_message_
boost::mutex last_detection_mutex_
 mutex to guard access to last_detection_message_
std::string namespace_gateway_
 namespace of the pipeline's sensor message gateway
ros::NodeHandle node_handle_
 ROS node handle.
bool sensor_message_gateway_open_
 > buffer for the last received detection
ros::ServiceServer service_server_start_recognition_
 Service server that starts the recognition pipeline.
ros::ServiceServer service_server_stop_recognition_
 Service server that stops the recognition pipeline.

Detailed Description

Definition at line 93 of file coordinator_node.h.


Constructor & Destructor Documentation

Definition at line 62 of file coordinator_node.cpp.

Definition at line 87 of file coordinator_node.cpp.


Member Function Documentation

void CoordinatorNode::detectionsCallback ( const cob_perception_msgs::DetectionArray::ConstPtr &  detection_array) [protected]

Definition at line 93 of file coordinator_node.cpp.

void CoordinatorNode::getDetectionsServerCallback ( const cob_people_detection::getDetectionsGoalConstPtr &  goal) [protected]

Definition at line 101 of file coordinator_node.cpp.

bool CoordinatorNode::startRecognitionCallback ( cob_people_detection::recognitionTrigger::Request &  req,
cob_people_detection::recognitionTrigger::Response &  res 
) [protected]

Definition at line 153 of file coordinator_node.cpp.

bool CoordinatorNode::stopRecognitionCallback ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  res 
) [protected]

Definition at line 168 of file coordinator_node.cpp.


Member Data Documentation

boost::mutex CoordinatorNode::active_action_mutex_ [protected]

mutex to avoid double call of an action

Definition at line 99 of file coordinator_node.h.

recieves messages of detections

Definition at line 106 of file coordinator_node.h.

Action server that handles requests for people detections.

Definition at line 109 of file coordinator_node.h.

cob_perception_msgs::DetectionArray CoordinatorNode::last_detection_message_ [protected]

Definition at line 101 of file coordinator_node.h.

boost::mutex CoordinatorNode::last_detection_mutex_ [protected]

mutex to guard access to last_detection_message_

Definition at line 100 of file coordinator_node.h.

std::string CoordinatorNode::namespace_gateway_ [protected]

namespace of the pipeline's sensor message gateway

Definition at line 116 of file coordinator_node.h.

ROS node handle.

Definition at line 97 of file coordinator_node.h.

> buffer for the last received detection

tracks whether the gateway was opened or not

Definition at line 103 of file coordinator_node.h.

Service server that starts the recognition pipeline.

Definition at line 112 of file coordinator_node.h.

Service server that stops the recognition pipeline.

Definition at line 113 of file coordinator_node.h.


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


cob_people_detection
Author(s): Richard Bormann , Thomas Zwölfer
autogenerated on Fri Aug 28 2015 10:24:13