Public Member Functions | Public Attributes | Private Member Functions | Static Private Member Functions | Private Attributes | List of all members
multi_robot_router::Router_Node Class Reference

#include <router_node.h>

Inheritance diagram for multi_robot_router::Router_Node:
Inheritance graph
[legend]

Public Member Functions

void monitorExecution ()
 monitors the execution More...
 
void publish ()
 publishes a RoutingTable More...
 
void publishEmpty ()
 publishes an empty RoutingTable More...
 
 Router_Node (ros::NodeHandle &n)
 Construct a new Router_Node object. More...
 
void updateTimeout (const float _secs)
 used to update the nodes timeout to latch topics More...
 

Public Attributes

ros::NodeHandle n_
 Node handler to the root node. More...
 
ros::NodeHandle n_param_
 Node handler to the current node. More...
 

Private Member Functions

float calcRadius (const int shape, const std::vector< float > &shape_variables) const
 
size_t getHash (const std::vector< signed char > &_map, const Eigen::Vector2d &_origin, const float &_resolution)
 
size_t getHash (const std::vector< Segment > &_graph)
 
float getYaw (const geometry_msgs::Quaternion &_rot)
 
void goalCallback (const geometry_msgs::PoseStamped &_goal)
 
void goalsCallback (const tuw_multi_robot_msgs::RobotGoalsArray &_goals)
 
void graphCallback (const tuw_multi_robot_msgs::Graph &msg)
 
void mapCallback (const nav_msgs::OccupancyGrid &_map)
 
void odomCallback (const ros::MessageEvent< nav_msgs::Odometry const > &_event, int _topic)
 
void parametersCallback (tuw_multi_robot_router::routerConfig &config, uint32_t level)
 
bool preparePlanning (std::vector< float > &_radius, std::vector< Eigen::Vector3d > &_starts, std::vector< Eigen::Vector3d > &_goals, const tuw_multi_robot_msgs::RobotGoalsArray &_ros_goals, std::vector< std::string > &robot_names)
 
void robotInfoCallback (const tuw_multi_robot_msgs::RobotInfo &_robotInfo)
 
void unsubscribeTopic (std::string _robot_name)
 
- Private Member Functions inherited from multi_robot_router::Router
uint32_t getDuration_ms () const
 getter More...
 
float getLongestPathLength () const
 getter More...
 
float getOverallPathLength () const
 getter More...
 
uint32_t getPriorityScheduleAttemps () const
 getter More...
 
const std::vector< Checkpoint > & getRoute (const uint32_t _robot) const
 returns the found Routing Table More...
 
uint32_t getSpeedScheduleAttemps () const
 getter More...
 
bool makePlan (const std::vector< Eigen::Vector3d > &_starts, const std::vector< Eigen::Vector3d > &_goals, const std::vector< float > &_radius, const cv::Mat &_map, const float &_resolution, const Eigen::Vector2d &_origin, const std::vector< Segment > &_graph, const std::vector< std::string > &_robot_names)
 generates the plan from (Vertex[odom robotPose] to Vertex[_goals] More...
 
void resize (const uint32_t _nr_robots)
 resizes the planner to a different nr of _nr_robots More...
 
 Router (const uint32_t _nr_robots)
 
 Router ()
 
void setCollisionResolutionType (const SegmentExpander::CollisionResolverType _cr)
 sets the CollisionResolverType used More...
 
void setPlannerType (routerType _type, uint32_t _nr_threads)
 

Static Private Member Functions

static bool sortSegments (const Segment &i, const Segment &j)
 

Private Attributes

std::vector< RobotInfoPtractive_robots_
 robots avaliable More...
 
int attempts_successful_
 
int attempts_total_
 
dynamic_reconfigure::Server< tuw_multi_robot_router::routerConfig >::CallbackType call_type
 
size_t current_graph_hash_
 
size_t current_map_hash_
 
cv::Mat distMap_
 
std::map< std::string, double > finished_robots_
 robots currently used by the planner More...
 
bool freshPlan_ = false
 
std::string goal_topic_
 
bool got_graph_ = false
 
bool got_map_ = false
 
std::vector< Segmentgraph_
 
int id_
 
std::string map_topic_
 
Eigen::Vector2d mapOrigin_
 
float mapResolution_
 
std::vector< std::string > missing_robots_
 robots finished with execution time More...
 
bool monitor_enabled_
 
tuw_multi_robot_msgs::RouterStatus mrrp_status_
 
std::string odom_topic_
 
dynamic_reconfigure::Server< tuw_multi_robot_router::routerConfig > param_server
 
std::string path_topic_
 
std::string planner_status_topic_
 
bool publish_routing_table_
 
ros::Publisher pubPlannerStatus_
 
std::string robot_info_topic_
 
float robot_radius_max_
 
std::string route_topic_
 
std::string singleRobotGoalTopic_
 
std::string singleRobotName_ = ""
 
ros::Subscriber subGoalSet_
 
ros::Subscriber subMap_
 
std::vector< ros::SubscribersubOdom_
 
ros::Subscriber subRobotInfo_
 
std::vector< RobotInfoPtrsubscribed_robots_
 
ros::Subscriber subSingleRobotGoal_
 
ros::Subscriber subVoronoiGraph_
 
double sum_processing_time_successful_
 
double sum_processing_time_total_
 
ros::Time time_first_robot_started_
 
float topic_timeout_s_ = 10
 
std::string voronoi_topic_
 
- Private Attributes inherited from multi_robot_router::Router
std::shared_ptr< float > potential_
 
bool collisionResolver_ = true
 
goalMode goalMode_ = goalMode::use_voronoi_goal
 
graphType graphMode_ = graphType::voronoi
 
bool priorityRescheduling_ = true
 
float routerTimeLimit_s_ = 10.0
 
bool segmentOptimizations_ = false
 
bool speedRescheduling_ = true
 

Additional Inherited Members

- Private Types inherited from multi_robot_router::Router
enum  goalMode { goalMode::use_segment_goal, goalMode::use_voronoi_goal, goalMode::use_map_goal }
 
enum  graphType { graphType::voronoi, graphType::random }
 
enum  routerType { routerType::singleThread, routerType::multiThreadSrr }
 

Detailed Description

Definition at line 53 of file router_node.h.

Constructor & Destructor Documentation

multi_robot_router::Router_Node::Router_Node ( ros::NodeHandle n)

Construct a new Router_Node object.

Parameters
nthe nodehandle to register publishers and subscribers

Definition at line 62 of file router_node.cpp.

Member Function Documentation

float multi_robot_router::Router_Node::calcRadius ( const int  shape,
const std::vector< float > &  shape_variables 
) const
private

Definition at line 231 of file router_node.cpp.

size_t multi_robot_router::Router_Node::getHash ( const std::vector< signed char > &  _map,
const Eigen::Vector2d &  _origin,
const float &  _resolution 
)
private

Definition at line 533 of file router_node.cpp.

std::size_t multi_robot_router::Router_Node::getHash ( const std::vector< Segment > &  _graph)
private

Definition at line 547 of file router_node.cpp.

float multi_robot_router::Router_Node::getYaw ( const geometry_msgs::Quaternion &  _rot)
private

Definition at line 393 of file router_node.cpp.

void multi_robot_router::Router_Node::goalCallback ( const geometry_msgs::PoseStamped &  _goal)
private

Definition at line 142 of file router_node.cpp.

void multi_robot_router::Router_Node::goalsCallback ( const tuw_multi_robot_msgs::RobotGoalsArray &  _goals)
private

Definition at line 341 of file router_node.cpp.

void multi_robot_router::Router_Node::graphCallback ( const tuw_multi_robot_msgs::Graph &  msg)
private

Definition at line 259 of file router_node.cpp.

void multi_robot_router::Router_Node::mapCallback ( const nav_msgs::OccupancyGrid &  _map)
private

Definition at line 199 of file router_node.cpp.

void multi_robot_router::Router_Node::monitorExecution ( )

monitors the execution

Definition at line 104 of file router_node.cpp.

void multi_robot_router::Router_Node::odomCallback ( const ros::MessageEvent< nav_msgs::Odometry const > &  _event,
int  _topic 
)
private
void multi_robot_router::Router_Node::parametersCallback ( tuw_multi_robot_router::routerConfig &  config,
uint32_t  level 
)
private

Definition at line 159 of file router_node.cpp.

bool multi_robot_router::Router_Node::preparePlanning ( std::vector< float > &  _radius,
std::vector< Eigen::Vector3d > &  _starts,
std::vector< Eigen::Vector3d > &  _goals,
const tuw_multi_robot_msgs::RobotGoalsArray &  _ros_goals,
std::vector< std::string > &  robot_names 
)
private

Definition at line 300 of file router_node.cpp.

void multi_robot_router::Router_Node::publish ( )

publishes a RoutingTable

Definition at line 424 of file router_node.cpp.

void multi_robot_router::Router_Node::publishEmpty ( )

publishes an empty RoutingTable

Definition at line 401 of file router_node.cpp.

void multi_robot_router::Router_Node::robotInfoCallback ( const tuw_multi_robot_msgs::RobotInfo &  _robotInfo)
private

Definition at line 240 of file router_node.cpp.

static bool multi_robot_router::Router_Node::sortSegments ( const Segment i,
const Segment j 
)
inlinestaticprivate

Definition at line 142 of file router_node.h.

void multi_robot_router::Router_Node::unsubscribeTopic ( std::string  _robot_name)
private
void multi_robot_router::Router_Node::updateTimeout ( const float  _secs)

used to update the nodes timeout to latch topics

Parameters
secsthe seconds passed since the last update

Definition at line 153 of file router_node.cpp.

Member Data Documentation

std::vector<RobotInfoPtr> multi_robot_router::Router_Node::active_robots_
private

robots avaliable

Definition at line 105 of file router_node.h.

int multi_robot_router::Router_Node::attempts_successful_
private

Definition at line 85 of file router_node.h.

int multi_robot_router::Router_Node::attempts_total_
private

Definition at line 84 of file router_node.h.

dynamic_reconfigure::Server<tuw_multi_robot_router::routerConfig>::CallbackType multi_robot_router::Router_Node::call_type
private

Definition at line 94 of file router_node.h.

size_t multi_robot_router::Router_Node::current_graph_hash_
private

Definition at line 126 of file router_node.h.

size_t multi_robot_router::Router_Node::current_map_hash_
private

Definition at line 125 of file router_node.h.

cv::Mat multi_robot_router::Router_Node::distMap_
private

Definition at line 109 of file router_node.h.

std::map<std::string, double> multi_robot_router::Router_Node::finished_robots_
private

robots currently used by the planner

Definition at line 106 of file router_node.h.

bool multi_robot_router::Router_Node::freshPlan_ = false
private

Definition at line 129 of file router_node.h.

std::string multi_robot_router::Router_Node::goal_topic_
private

Definition at line 115 of file router_node.h.

bool multi_robot_router::Router_Node::got_graph_ = false
private

Definition at line 123 of file router_node.h.

bool multi_robot_router::Router_Node::got_map_ = false
private

Definition at line 122 of file router_node.h.

std::vector<Segment> multi_robot_router::Router_Node::graph_
private

Definition at line 124 of file router_node.h.

int multi_robot_router::Router_Node::id_
private

Definition at line 127 of file router_node.h.

std::string multi_robot_router::Router_Node::map_topic_
private

Definition at line 116 of file router_node.h.

Eigen::Vector2d multi_robot_router::Router_Node::mapOrigin_
private

Definition at line 110 of file router_node.h.

float multi_robot_router::Router_Node::mapResolution_
private

Definition at line 111 of file router_node.h.

std::vector<std::string> multi_robot_router::Router_Node::missing_robots_
private

robots finished with execution time

Definition at line 107 of file router_node.h.

bool multi_robot_router::Router_Node::monitor_enabled_
private

Definition at line 131 of file router_node.h.

tuw_multi_robot_msgs::RouterStatus multi_robot_router::Router_Node::mrrp_status_
private

Definition at line 91 of file router_node.h.

ros::NodeHandle multi_robot_router::Router_Node::n_

Node handler to the root node.

Definition at line 79 of file router_node.h.

ros::NodeHandle multi_robot_router::Router_Node::n_param_

Node handler to the current node.

Definition at line 80 of file router_node.h.

std::string multi_robot_router::Router_Node::odom_topic_
private

Definition at line 113 of file router_node.h.

dynamic_reconfigure::Server<tuw_multi_robot_router::routerConfig> multi_robot_router::Router_Node::param_server
private

Definition at line 93 of file router_node.h.

std::string multi_robot_router::Router_Node::path_topic_
private

Definition at line 114 of file router_node.h.

std::string multi_robot_router::Router_Node::planner_status_topic_
private

Definition at line 119 of file router_node.h.

bool multi_robot_router::Router_Node::publish_routing_table_
private

Definition at line 121 of file router_node.h.

ros::Publisher multi_robot_router::Router_Node::pubPlannerStatus_
private

Definition at line 95 of file router_node.h.

std::string multi_robot_router::Router_Node::robot_info_topic_
private

Definition at line 117 of file router_node.h.

float multi_robot_router::Router_Node::robot_radius_max_
private

Definition at line 108 of file router_node.h.

std::string multi_robot_router::Router_Node::route_topic_
private

Definition at line 112 of file router_node.h.

std::string multi_robot_router::Router_Node::singleRobotGoalTopic_
private

Definition at line 120 of file router_node.h.

std::string multi_robot_router::Router_Node::singleRobotName_ = ""
private

Definition at line 130 of file router_node.h.

ros::Subscriber multi_robot_router::Router_Node::subGoalSet_
private

Definition at line 98 of file router_node.h.

ros::Subscriber multi_robot_router::Router_Node::subMap_
private

Definition at line 99 of file router_node.h.

std::vector<ros::Subscriber> multi_robot_router::Router_Node::subOdom_
private

Definition at line 97 of file router_node.h.

ros::Subscriber multi_robot_router::Router_Node::subRobotInfo_
private

Definition at line 102 of file router_node.h.

std::vector<RobotInfoPtr> multi_robot_router::Router_Node::subscribed_robots_
private

Definition at line 104 of file router_node.h.

ros::Subscriber multi_robot_router::Router_Node::subSingleRobotGoal_
private

Definition at line 100 of file router_node.h.

ros::Subscriber multi_robot_router::Router_Node::subVoronoiGraph_
private

Definition at line 101 of file router_node.h.

double multi_robot_router::Router_Node::sum_processing_time_successful_
private

Definition at line 87 of file router_node.h.

double multi_robot_router::Router_Node::sum_processing_time_total_
private

Definition at line 86 of file router_node.h.

ros::Time multi_robot_router::Router_Node::time_first_robot_started_
private

Definition at line 89 of file router_node.h.

float multi_robot_router::Router_Node::topic_timeout_s_ = 10
private

Definition at line 128 of file router_node.h.

std::string multi_robot_router::Router_Node::voronoi_topic_
private

Definition at line 118 of file router_node.h.


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


tuw_multi_robot_router
Author(s): Benjamin Binder
autogenerated on Mon Jun 10 2019 15:42:49