#include <router_node.h>
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) |
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 } |
Definition at line 53 of file router_node.h.
multi_robot_router::Router_Node::Router_Node | ( | ros::NodeHandle & | n | ) |
Construct a new Router_Node object.
n | the nodehandle to register publishers and subscribers |
Definition at line 62 of file router_node.cpp.
|
private |
Definition at line 231 of file router_node.cpp.
|
private |
Definition at line 533 of file router_node.cpp.
|
private |
Definition at line 547 of file router_node.cpp.
|
private |
Definition at line 393 of file router_node.cpp.
|
private |
Definition at line 142 of file router_node.cpp.
|
private |
Definition at line 341 of file router_node.cpp.
|
private |
Definition at line 259 of file router_node.cpp.
|
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.
|
private |
|
private |
Definition at line 159 of file router_node.cpp.
|
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.
|
private |
Definition at line 240 of file router_node.cpp.
|
inlinestaticprivate |
Definition at line 142 of file router_node.h.
|
private |
void multi_robot_router::Router_Node::updateTimeout | ( | const float | _secs | ) |
used to update the nodes timeout to latch topics
secs | the seconds passed since the last update |
Definition at line 153 of file router_node.cpp.
|
private |
robots avaliable
Definition at line 105 of file router_node.h.
|
private |
Definition at line 85 of file router_node.h.
|
private |
Definition at line 84 of file router_node.h.
|
private |
Definition at line 94 of file router_node.h.
|
private |
Definition at line 126 of file router_node.h.
|
private |
Definition at line 125 of file router_node.h.
|
private |
Definition at line 109 of file router_node.h.
|
private |
robots currently used by the planner
Definition at line 106 of file router_node.h.
|
private |
Definition at line 129 of file router_node.h.
|
private |
Definition at line 115 of file router_node.h.
|
private |
Definition at line 123 of file router_node.h.
|
private |
Definition at line 122 of file router_node.h.
|
private |
Definition at line 124 of file router_node.h.
|
private |
Definition at line 127 of file router_node.h.
|
private |
Definition at line 116 of file router_node.h.
|
private |
Definition at line 110 of file router_node.h.
|
private |
Definition at line 111 of file router_node.h.
|
private |
robots finished with execution time
Definition at line 107 of file router_node.h.
|
private |
Definition at line 131 of file router_node.h.
|
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.
|
private |
Definition at line 113 of file router_node.h.
|
private |
Definition at line 93 of file router_node.h.
|
private |
Definition at line 114 of file router_node.h.
|
private |
Definition at line 119 of file router_node.h.
|
private |
Definition at line 121 of file router_node.h.
|
private |
Definition at line 95 of file router_node.h.
|
private |
Definition at line 117 of file router_node.h.
|
private |
Definition at line 108 of file router_node.h.
|
private |
Definition at line 112 of file router_node.h.
|
private |
Definition at line 120 of file router_node.h.
|
private |
Definition at line 130 of file router_node.h.
|
private |
Definition at line 98 of file router_node.h.
|
private |
Definition at line 99 of file router_node.h.
|
private |
Definition at line 97 of file router_node.h.
|
private |
Definition at line 102 of file router_node.h.
|
private |
Definition at line 104 of file router_node.h.
|
private |
Definition at line 100 of file router_node.h.
|
private |
Definition at line 101 of file router_node.h.
|
private |
Definition at line 87 of file router_node.h.
|
private |
Definition at line 86 of file router_node.h.
|
private |
Definition at line 89 of file router_node.h.
|
private |
Definition at line 128 of file router_node.h.
|
private |
Definition at line 118 of file router_node.h.