Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | List of all members
tuw_multi_robot_route_to_path::MultiRobotRouteToPathNode Class Reference

#include <MultiRobotRouteToPathNode.h>

Public Member Functions

 MultiRobotRouteToPathNode (ros::NodeHandle &n)
 

Public Attributes

ros::NodeHandle n_
 Node handler to the root node. More...
 
ros::NodeHandle n_param_
 Node handler to the current node. More...
 
std::unique_ptr< ros::Raterate_
 

Private Member Functions

int findRobotId (std::string _name)
 
void publishPath (std::vector< Eigen::Vector3d > _p, int _topic)
 
void subOdomCb (const ros::MessageEvent< nav_msgs::Odometry const > &_event, int _topic)
 
void subSegPathCb (const ros::MessageEvent< tuw_multi_robot_msgs::Route const > &_event, int _topic)
 

Private Attributes

std::vector< RobotRouteToPathconverter_
 
int no_robots_
 
std::vector< RobotStateObserverobserver_
 
std::vector< ros::PublisherpubPath_
 
std::vector< std::string > robot_names_
 
std::vector< int > robot_steps_
 
std::vector< ros::SubscribersubOdometry_
 
std::vector< ros::SubscribersubSegPath_
 
std::string topic_odom_
 
std::string topic_path_
 
std::string topic_seg_path_
 

Detailed Description

Definition at line 42 of file MultiRobotRouteToPathNode.h.

Constructor & Destructor Documentation

tuw_multi_robot_route_to_path::MultiRobotRouteToPathNode::MultiRobotRouteToPathNode ( ros::NodeHandle n)

Definition at line 50 of file MultiRobotRouteToPathNode.cpp.

Member Function Documentation

int tuw_multi_robot_route_to_path::MultiRobotRouteToPathNode::findRobotId ( std::string  _name)
private

Definition at line 160 of file MultiRobotRouteToPathNode.cpp.

void tuw_multi_robot_route_to_path::MultiRobotRouteToPathNode::publishPath ( std::vector< Eigen::Vector3d >  _p,
int  _topic 
)
private

Definition at line 129 of file MultiRobotRouteToPathNode.cpp.

void tuw_multi_robot_route_to_path::MultiRobotRouteToPathNode::subOdomCb ( const ros::MessageEvent< nav_msgs::Odometry const > &  _event,
int  _topic 
)
private

Definition at line 105 of file MultiRobotRouteToPathNode.cpp.

void tuw_multi_robot_route_to_path::MultiRobotRouteToPathNode::subSegPathCb ( const ros::MessageEvent< tuw_multi_robot_msgs::Route const > &  _event,
int  _topic 
)
private

Definition at line 171 of file MultiRobotRouteToPathNode.cpp.

Member Data Documentation

std::vector<RobotRouteToPath> tuw_multi_robot_route_to_path::MultiRobotRouteToPathNode::converter_
private

Definition at line 70 of file MultiRobotRouteToPathNode.h.

ros::NodeHandle tuw_multi_robot_route_to_path::MultiRobotRouteToPathNode::n_

Node handler to the root node.

Definition at line 49 of file MultiRobotRouteToPathNode.h.

ros::NodeHandle tuw_multi_robot_route_to_path::MultiRobotRouteToPathNode::n_param_

Node handler to the current node.

Definition at line 50 of file MultiRobotRouteToPathNode.h.

int tuw_multi_robot_route_to_path::MultiRobotRouteToPathNode::no_robots_
private

Definition at line 72 of file MultiRobotRouteToPathNode.h.

std::vector<RobotStateObserver> tuw_multi_robot_route_to_path::MultiRobotRouteToPathNode::observer_
private

Definition at line 71 of file MultiRobotRouteToPathNode.h.

std::vector<ros::Publisher> tuw_multi_robot_route_to_path::MultiRobotRouteToPathNode::pubPath_
private

Definition at line 56 of file MultiRobotRouteToPathNode.h.

std::unique_ptr<ros::Rate> tuw_multi_robot_route_to_path::MultiRobotRouteToPathNode::rate_

Definition at line 51 of file MultiRobotRouteToPathNode.h.

std::vector<std::string> tuw_multi_robot_route_to_path::MultiRobotRouteToPathNode::robot_names_
private

Definition at line 64 of file MultiRobotRouteToPathNode.h.

std::vector<int> tuw_multi_robot_route_to_path::MultiRobotRouteToPathNode::robot_steps_
private

Definition at line 73 of file MultiRobotRouteToPathNode.h.

std::vector<ros::Subscriber> tuw_multi_robot_route_to_path::MultiRobotRouteToPathNode::subOdometry_
private

Definition at line 58 of file MultiRobotRouteToPathNode.h.

std::vector<ros::Subscriber> tuw_multi_robot_route_to_path::MultiRobotRouteToPathNode::subSegPath_
private

Definition at line 57 of file MultiRobotRouteToPathNode.h.

std::string tuw_multi_robot_route_to_path::MultiRobotRouteToPathNode::topic_odom_
private

Definition at line 63 of file MultiRobotRouteToPathNode.h.

std::string tuw_multi_robot_route_to_path::MultiRobotRouteToPathNode::topic_path_
private

Definition at line 61 of file MultiRobotRouteToPathNode.h.

std::string tuw_multi_robot_route_to_path::MultiRobotRouteToPathNode::topic_seg_path_
private

Definition at line 62 of file MultiRobotRouteToPathNode.h.


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


tuw_multi_robot_route_to_path
Author(s): Benjamin Binder
autogenerated on Fri Jun 22 2018 03:07:12