Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | List of all members
velocity_controller::LocalMultiRobotControllerNode Class Reference

#include <local_multi_robot_controller_node.h>

Public Member Functions

 LocalMultiRobotControllerNode (ros::NodeHandle &n)
 Construct a new Multi Segment Controller Node object. More...
 
void publishRobotInfo ()
 publish the robot info of each robot More...
 

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 robot_name)
 
void subCtrlCb (const ros::MessageEvent< std_msgs::String const > &_event, int _topic)
 
void subOdomCb (const ros::MessageEvent< nav_msgs::Odometry const > &_event, int _topic)
 
void subRouteCb (const ros::MessageEvent< tuw_multi_robot_msgs::Route const > &_event, int _topic)
 

Private Attributes

std::vector< bool > active_robots = {false}
 
std::vector< SegmentControllercontroller
 
bool first_path_set_ = {false}
 
std::string frame_map_
 
ros::Time global_tic
 
float goal_r_
 
float Kd_val_
 
float Ki_val_
 
float Kp_val_
 
ros::Time last_update_
 
float max_vel_v_
 
float max_vel_w_
 
int nr_of_finished_ = {0}
 
int nr_of_robots_
 
std::vector< ros::PublisherpubCmdVel_
 
ros::Publisher pubRobotInfo_
 
std::vector< std::string > robot_names_
 
std::vector< geometry_msgs::PoseWithCovariance > robot_pose_
 
std::string robot_prefix_
 
std::vector< float > robot_radius_
 
std::vector< ros::SubscribersubCtrl_
 
std::vector< ros::SubscribersubOdom_
 
std::vector< ros::SubscribersubRoute_
 
std::string topic_cmdVel_
 
std::string topic_ctrl_
 
std::string topic_odom_
 
std::string topic_robot_info_
 
std::string topic_route_
 
double update_rate_
 

Detailed Description

Definition at line 18 of file local_multi_robot_controller_node.h.

Constructor & Destructor Documentation

velocity_controller::LocalMultiRobotControllerNode::LocalMultiRobotControllerNode ( ros::NodeHandle n)

Construct a new Multi Segment Controller Node object.

Parameters
nthe node handle to subscribe to topics

Definition at line 27 of file local_multi_robot_controller_node.cpp.

Member Function Documentation

int velocity_controller::LocalMultiRobotControllerNode::findRobotId ( std::string  robot_name)
private

Definition at line 230 of file local_multi_robot_controller_node.cpp.

void velocity_controller::LocalMultiRobotControllerNode::publishRobotInfo ( )

publish the robot info of each robot

Definition at line 266 of file local_multi_robot_controller_node.cpp.

void velocity_controller::LocalMultiRobotControllerNode::subCtrlCb ( const ros::MessageEvent< std_msgs::String const > &  _event,
int  _topic 
)
private

Definition at line 241 of file local_multi_robot_controller_node.cpp.

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

Definition at line 145 of file local_multi_robot_controller_node.cpp.

void velocity_controller::LocalMultiRobotControllerNode::subRouteCb ( const ros::MessageEvent< tuw_multi_robot_msgs::Route const > &  _event,
int  _topic 
)
private

Definition at line 194 of file local_multi_robot_controller_node.cpp.

Member Data Documentation

std::vector<bool> velocity_controller::LocalMultiRobotControllerNode::active_robots = {false}
private

Definition at line 57 of file local_multi_robot_controller_node.h.

std::vector<SegmentController> velocity_controller::LocalMultiRobotControllerNode::controller
private

Definition at line 67 of file local_multi_robot_controller_node.h.

bool velocity_controller::LocalMultiRobotControllerNode::first_path_set_ = {false}
private

Definition at line 58 of file local_multi_robot_controller_node.h.

std::string velocity_controller::LocalMultiRobotControllerNode::frame_map_
private

Definition at line 46 of file local_multi_robot_controller_node.h.

ros::Time velocity_controller::LocalMultiRobotControllerNode::global_tic
private

Definition at line 59 of file local_multi_robot_controller_node.h.

float velocity_controller::LocalMultiRobotControllerNode::goal_r_
private

Definition at line 50 of file local_multi_robot_controller_node.h.

float velocity_controller::LocalMultiRobotControllerNode::Kd_val_
private

Definition at line 53 of file local_multi_robot_controller_node.h.

float velocity_controller::LocalMultiRobotControllerNode::Ki_val_
private

Definition at line 52 of file local_multi_robot_controller_node.h.

float velocity_controller::LocalMultiRobotControllerNode::Kp_val_
private

Definition at line 51 of file local_multi_robot_controller_node.h.

ros::Time velocity_controller::LocalMultiRobotControllerNode::last_update_
private

Definition at line 54 of file local_multi_robot_controller_node.h.

float velocity_controller::LocalMultiRobotControllerNode::max_vel_v_
private

Definition at line 48 of file local_multi_robot_controller_node.h.

float velocity_controller::LocalMultiRobotControllerNode::max_vel_w_
private

Definition at line 49 of file local_multi_robot_controller_node.h.

ros::NodeHandle velocity_controller::LocalMultiRobotControllerNode::n_

Node handler to the root node.

Definition at line 27 of file local_multi_robot_controller_node.h.

ros::NodeHandle velocity_controller::LocalMultiRobotControllerNode::n_param_

Node handler to the current node.

Definition at line 28 of file local_multi_robot_controller_node.h.

int velocity_controller::LocalMultiRobotControllerNode::nr_of_finished_ = {0}
private

Definition at line 56 of file local_multi_robot_controller_node.h.

int velocity_controller::LocalMultiRobotControllerNode::nr_of_robots_
private

Definition at line 55 of file local_multi_robot_controller_node.h.

std::vector<ros::Publisher> velocity_controller::LocalMultiRobotControllerNode::pubCmdVel_
private

Definition at line 36 of file local_multi_robot_controller_node.h.

ros::Publisher velocity_controller::LocalMultiRobotControllerNode::pubRobotInfo_
private

Definition at line 37 of file local_multi_robot_controller_node.h.

std::unique_ptr<ros::Rate> velocity_controller::LocalMultiRobotControllerNode::rate_

Definition at line 29 of file local_multi_robot_controller_node.h.

std::vector<std::string> velocity_controller::LocalMultiRobotControllerNode::robot_names_
private

Definition at line 61 of file local_multi_robot_controller_node.h.

std::vector<geometry_msgs::PoseWithCovariance> velocity_controller::LocalMultiRobotControllerNode::robot_pose_
private

Definition at line 63 of file local_multi_robot_controller_node.h.

std::string velocity_controller::LocalMultiRobotControllerNode::robot_prefix_
private

Definition at line 60 of file local_multi_robot_controller_node.h.

std::vector<float> velocity_controller::LocalMultiRobotControllerNode::robot_radius_
private

Definition at line 62 of file local_multi_robot_controller_node.h.

std::vector<ros::Subscriber> velocity_controller::LocalMultiRobotControllerNode::subCtrl_
private

Definition at line 40 of file local_multi_robot_controller_node.h.

std::vector<ros::Subscriber> velocity_controller::LocalMultiRobotControllerNode::subOdom_
private

Definition at line 38 of file local_multi_robot_controller_node.h.

std::vector<ros::Subscriber> velocity_controller::LocalMultiRobotControllerNode::subRoute_
private

Definition at line 39 of file local_multi_robot_controller_node.h.

std::string velocity_controller::LocalMultiRobotControllerNode::topic_cmdVel_
private

Definition at line 41 of file local_multi_robot_controller_node.h.

std::string velocity_controller::LocalMultiRobotControllerNode::topic_ctrl_
private

Definition at line 44 of file local_multi_robot_controller_node.h.

std::string velocity_controller::LocalMultiRobotControllerNode::topic_odom_
private

Definition at line 42 of file local_multi_robot_controller_node.h.

std::string velocity_controller::LocalMultiRobotControllerNode::topic_robot_info_
private

Definition at line 45 of file local_multi_robot_controller_node.h.

std::string velocity_controller::LocalMultiRobotControllerNode::topic_route_
private

Definition at line 43 of file local_multi_robot_controller_node.h.

double velocity_controller::LocalMultiRobotControllerNode::update_rate_
private

Definition at line 47 of file local_multi_robot_controller_node.h.


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


tuw_multi_robot_ctrl
Author(s): Benjamin Binder
autogenerated on Mon Jun 10 2019 15:42:29