Provides a global planner that will make a route along check points gained from topic. This planner uses global_planner. More...
#include <ppplanner.h>

Classes | |
| struct | asegment |
Public Member Functions | |
| void | initialize (std::string name, costmap_2d::Costmap2DROS *costmap_ros) |
| Initialisation function for the Planner. More... | |
| bool | initialize (std::string name, costmap_2d::Costmap2D *costmap, std::string frame_id) |
| Initialisation function for the Planner. More... | |
| bool | makePlan (const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan) |
| Given a goal pose in the world, compute a plan. More... | |
| PipelinePlanner () | |
| Constructor for the PipelinePlanner. More... | |
| PipelinePlanner (std::string name, costmap_2d::Costmap2D *costmap, std::string frame_id) | |
| Constructor for the PipelinePlanner. More... | |
| bool | ReceiveCheckpoints (pipeline_planner::ReceiveCheckpoints::Request &req, pipeline_planner::ReceiveCheckpoints::Response &res) |
| Reception of checkpoints. More... | |
| void | setCharge (bool charge) |
| void | setLethal (unsigned char lethal_cost) |
| void | setNumThread (float num_threads) |
| void | setPipeRadius (float radius) |
| substitute pipe_radius_ value when it is called from dynamic reconfigure More... | |
| void | setStraight (bool use_straight) |
| void | setTimeDisplay (bool time_display) |
| void | setTorchArea (bool use_torch, float torch_area_x, float torch_area_y) |
| void | setWeight (float centre_weight) |
| ~PipelinePlanner () | |
| Destructor for the planner. More... | |
Public Member Functions inherited from nav_core::BaseGlobalPlanner | |
| virtual bool | makePlan (const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan, double &cost) |
| virtual | ~BaseGlobalPlanner () |
Private Member Functions | |
| void | calcPipeline (const int numcheckpoints, const double *stonex, const double *stoney, const bool isClose, const double *radii, const double *sradii, const double *eradii, const double origin_x, const double origin_y, const unsigned int costsizex, const unsigned int costsizey, const double resolution, int *data) |
| To calculate the pipeline without GPU. More... | |
| void | callbackgoal (const move_base_msgs::MoveBaseActionGoal::ConstPtr &goal) |
| Callback function for reception of actionlib goal. More... | |
| void | callbackRobotPose (const geometry_msgs::Pose::ConstPtr &pose) |
| Callback function for reception of robot position. More... | |
| bool | ConnectPoints (const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, const std::vector< int > segids, std::vector< geometry_msgs::PoseStamped > &plan) |
| To substitute plan by connecting start point, checkpoints and goal point. More... | |
| int | costCheck (int endpoint) |
| To check received checkpoints whether it has a problem on costmap or not. More... | |
| int | CrossTorchArea (const double tx, const double ty, const double sx, const double sy, const double ex, const double ey, double &bx, double &by) |
| Whether the line segment crosses the torch area boundary or not. More... | |
| bool | DistanceFromCentre (int endpoint) |
| Calculation of cell's distance from pipe centre. More... | |
| bool | DistanceFromCentre_cuda (int endpoint) |
| Calculation of cell's distance from pipe centre. More... | |
| bool | DrawOpenSegment (const geometry_msgs::PoseStamped init_point, const geometry_msgs::PoseStamped end_point, std::vector< geometry_msgs::PoseStamped > &plan) |
| To substitute the plan along two points. More... | |
| bool | getCheckpoints (pipeline_planner::GetCheckpoints::Request &req, pipeline_planner::GetCheckpoints::Response &res) |
| Get check points. More... | |
| bool | getNumofCheckpoints (pipeline_planner::GetNumofCheckpoints::Request &req, pipeline_planner::GetNumofCheckpoints::Response &res) |
| Get the status of reading checkpoints. More... | |
| bool | getReadStatus (pipeline_planner::GetReadStatus::Request &req, pipeline_planner::GetReadStatus::Response &res) |
| Get the status of reading checkpoints. More... | |
| bool | getRobotStatus (pipeline_planner::GetRobotStatus::Request &req, pipeline_planner::GetRobotStatus::Response &res) |
| Get the status of a robot. More... | |
| bool | hasNoCross (const int endpoint, const std::vector< geometry_msgs::PoseStamped > check_points) |
| To check whether a sequence of checkpoints has a crossing or not. More... | |
| void | informRobotPose () |
| loop for informing the robot position by a thread More... | |
| bool | InitSegInfo () |
| Initialisation of segment info. More... | |
| bool | InPipeSegment (const geometry_msgs::PoseStamped &pose, double radius, double start_edge_radius, double end_edge_radius, double tolerance, int index) |
| Verification of whether the position is in the pipeline segment or not. More... | |
| bool | InquireSegments (pipeline_planner::InquireSegments::Request &req, pipeline_planner::InquireSegments::Response &res) |
| Inquiring segments information. More... | |
| bool | isBehindInaSegment (int idx, const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal) |
| Whether the goal point is behind the start point in a pipe segment. More... | |
| bool | knowRobotPosition (const geometry_msgs::Pose pose, int &ID, double &distance) |
| To know the position of a robot in the pipeline. More... | |
| void | makePipeline () |
| To make a pipeline and publish it as a topic Pipeline is constructed from check_points_. Validity of checkpoints_ must be checked in advance. Publication data values 0:in the pipeline, 100:out of the pipeline. More... | |
| void | makePipeline (bool legal) |
| void | PublishCheckpointsResult (std_msgs::UInt32 result) |
| Callback function for subscription of checkpoints data from topic. More... | |
| void | publishPlan (const std::vector< geometry_msgs::PoseStamped > &path) |
| To publish a path. More... | |
| void | reconfigureCB (pipeline_planner::PipelinePlannerConfig &config, uint32_t level) |
| Callback function for dynamic reconfiguration. More... | |
| bool | SetARadius (pipeline_planner::SetARadius::Request &req, pipeline_planner::SetARadius::Response &res) |
| Service to set a pipeline segment radius. More... | |
| bool | SetARightshift (pipeline_planner::SetARightshift::Request &req, pipeline_planner::SetARightshift::Response &res) |
| Service to set a right shift value for a pipeline segment. More... | |
| bool | TakeLocalGoal (const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, geometry_msgs::PoseStamped &local_goal, int &err) |
| To make local goal on torch model. More... | |
| double | TakeSegmentRadius (const double contained_radius) |
| Taking pipline radius in a given pipeline segment. More... | |
| void | ThreadNumberAdjusment (bool debug) |
| void | TimeDisplay (const bool time_display, const double duration) |
| Display consumed time on makePlan function. More... | |
| bool | VeilCostmap (const std::vector< int > segids, const int startindex, const int goalindex, const geometry_msgs::PoseStamped &start) |
| To veil costmap other than that in pipeline segments. More... | |
| bool | VeilCostmap_cuda (const std::vector< int > segids, const int startindex, const int goalindex, const geometry_msgs::PoseStamped &start) |
| To veil costmap other than that in pipeline segments. More... | |
| bool | whereInaPipeSegment (const geometry_msgs::Pose pose, const int id, const double radius, const double sradius, const double eradius, int &part, double &dist, double tolerance) |
| To know the position of a robot in a pipe segment. More... | |
Additional Inherited Members | |
Protected Member Functions inherited from nav_core::BaseGlobalPlanner | |
| BaseGlobalPlanner () | |
Provides a global planner that will make a route along check points gained from topic. This planner uses global_planner.
Definition at line 75 of file ppplanner.h.
| pipeline_planner::PipelinePlanner::PipelinePlanner | ( | ) |
Constructor for the PipelinePlanner.
Definition at line 80 of file ppplanner_core.cpp.
| pipeline_planner::PipelinePlanner::PipelinePlanner | ( | std::string | name, |
| costmap_2d::Costmap2D * | costmap, | ||
| std::string | frame_id | ||
| ) |
Constructor for the PipelinePlanner.
| name | The name of this planner |
| costmap | A pointer for the costmap |
Definition at line 85 of file ppplanner_core.cpp.
| pipeline_planner::PipelinePlanner::~PipelinePlanner | ( | ) |
Destructor for the planner.
Definition at line 92 of file ppplanner_core.cpp.
|
private |
To calculate the pipeline without GPU.
Definition at line 2117 of file ppplanner_core.cpp.
|
private |
Callback function for reception of actionlib goal.
| goal | callback message |
Definition at line 2194 of file ppplanner_core.cpp.
|
private |
Callback function for reception of robot position.
| pose | callback message |
Definition at line 2198 of file ppplanner_core.cpp.
|
private |
To substitute plan by connecting start point, checkpoints and goal point.
| start | The start pose |
| goal | The goal pose |
| segids | IDs for checkpoints to use |
| plan | The plan, which will be filled by the function |
Definition at line 1880 of file ppplanner_core.cpp.
|
private |
To check received checkpoints whether it has a problem on costmap or not.
| endpoint | The last point of received checkpoints sequence |
Definition at line 450 of file ppplanner_core.cpp.
|
private |
Whether the line segment crosses the torch area boundary or not.
| tx | The centre of torch area x |
| ty | The centre of torch area y |
| sx | The start of the line segment x |
| sy | The start of the line segment y |
| ex | The end of the line segment x |
| ey | The end of the line segment y |
| bx | The gained corss point x |
| by | The gained corss point y |
Definition at line 2385 of file ppplanner_core.cpp.
|
private |
Calculation of cell's distance from pipe centre.
| endpoint | The last point of received checkpoints sequence |
Definition at line 543 of file ppplanner_core.cpp.
|
private |
Calculation of cell's distance from pipe centre.
| endpoint | The last point of received checkpoints sequence |
Definition at line 615 of file ppplanner_core.cpp.
|
private |
To substitute the plan along two points.
| init_point | Initial point |
| end_point | End point |
| plan | The plan, which will be filled by the function |
Definition at line 1931 of file ppplanner_core.cpp.
|
inlineprivate |
Get check points.
| req | Dummy argument for input |
| res | The check points and the open close flag |
Definition at line 205 of file ppplanner.h.
|
inlineprivate |
Get the status of reading checkpoints.
| req | Dummy argument for input |
| res | The status of reading checkpoints for output |
Definition at line 228 of file ppplanner.h.
|
inlineprivate |
Get the status of reading checkpoints.
| req | Dummy argument for input |
| res | The status of reading checkpoints for output |
Definition at line 183 of file ppplanner.h.
|
inlineprivate |
Get the status of a robot.
| req | Dummy argument for input |
| res | The status of a robot for output |
Definition at line 194 of file ppplanner.h.
|
private |
To check whether a sequence of checkpoints has a crossing or not.
| endpoint | The last point of checkpoints sequence. It depends on openclose flag. |
| check_points | Received checkpoints |
Definition at line 377 of file ppplanner_core.cpp.
|
private |
loop for informing the robot position by a thread
Definition at line 2205 of file ppplanner_core.cpp.
|
virtual |
Initialisation function for the Planner.
| name | The name of this planner |
| costmap_ros | A pointer to the ROS wrapper of the costmap to use for planning |
Implements nav_core::BaseGlobalPlanner.
Definition at line 100 of file ppplanner_core.cpp.
| bool pipeline_planner::PipelinePlanner::initialize | ( | std::string | name, |
| costmap_2d::Costmap2D * | costmap, | ||
| std::string | frame_id | ||
| ) |
Initialisation function for the Planner.
| name | The name of this planner |
| costmap | A pointer to the costmap |
| frame_id | The global frame of the costmap |
Definition at line 120 of file ppplanner_core.cpp.
|
private |
Initialisation of segment info.
Definition at line 715 of file ppplanner_core.cpp.
|
private |
Verification of whether the position is in the pipeline segment or not.
| pose | The position for verification |
| radius | The radius of the pipeline |
| start_edge_radius | The radius for start edge circle |
| end_edge_radius | The radius for end edge circle |
| tolerance | The minimum value of the length of the pipeline segment |
| index | The index of the pipeline segment |
Definition at line 1282 of file ppplanner_core.cpp.
|
private |
Inquiring segments information.
| req | Dummy argument for input |
| res | The information of segments |
Definition at line 762 of file ppplanner_core.cpp.
|
private |
Whether the goal point is behind the start point in a pipe segment.
| idx | Index of the pipeline segment |
| start | Start position |
| goal | Goal position |
Definition at line 1500 of file ppplanner_core.cpp.
|
private |
To know the position of a robot in the pipeline.
| pose | The position of the robot |
| ID | ID number for the pipesegment to which the robot belongs |
| distance | The distance from start check point in the pipe segment to which the robot belongs |
Definition at line 1328 of file ppplanner_core.cpp.
|
private |
To make a pipeline and publish it as a topic Pipeline is constructed from check_points_. Validity of checkpoints_ must be checked in advance. Publication data values 0:in the pipeline, 100:out of the pipeline.
Definition at line 1995 of file ppplanner_core.cpp.
|
private |
Definition at line 2000 of file ppplanner_core.cpp.
|
virtual |
Given a goal pose in the world, compute a plan.
| start | The start pose |
| goal | The goal pose |
| plan | The plan... filled by the planner |
Implements nav_core::BaseGlobalPlanner.
Definition at line 986 of file ppplanner_core.cpp.
|
private |
Callback function for subscription of checkpoints data from topic.
| checkpoints | Checkpoints data from topic checkpoints->header.frame_id is whether the route is closed or not 1:closed, 2:opened Publication of result of reading check points |
| result | Result status |
Definition at line 758 of file ppplanner_core.cpp.
|
private |
To publish a path.
| path | Path to be published |
Definition at line 1980 of file ppplanner_core.cpp.
| bool pipeline_planner::PipelinePlanner::ReceiveCheckpoints | ( | pipeline_planner::ReceiveCheckpoints::Request & | req, |
| pipeline_planner::ReceiveCheckpoints::Response & | res | ||
| ) |
Reception of checkpoints.
| req | Checkpoints for reception |
| res | Status of receiving checkpoints |
Definition at line 778 of file ppplanner_core.cpp.
|
private |
Callback function for dynamic reconfiguration.
| config | The new configuration |
| level | ORing together level values of the parameters |
Definition at line 203 of file ppplanner_core.cpp.
|
private |
Service to set a pipeline segment radius.
| req | ID and radius for new pipeline segment radius |
| res | The result and the updated value for status of reading checkpoints req.ID -1: all pipeline segment others: pipeline segment ID res.result 0: accepted normally (only normal state) 1: ID is not -1, 0 nor positive 2: The value is illegal, id est, other than 0.0 or [0.001,50]. 0.0 means it follows pipe_radius value. 3: A set of checkpoints is empty 4: ID is larger than the number of checkpoints |
Definition at line 264 of file ppplanner_core.cpp.
|
private |
Service to set a right shift value for a pipeline segment.
| req | ID and right shift value for the pipeline segment |
| res | The result. res.result 0: accepted normally (only normal state) 1: ID value is not -1, 0 nor positive 3: A set of checkpoints is empty 4: ID is larger than the number of checkpoints |
Definition at line 340 of file ppplanner_core.cpp.
|
inline |
Definition at line 142 of file ppplanner.h.
|
inline |
Definition at line 124 of file ppplanner.h.
|
inline |
Definition at line 133 of file ppplanner.h.
| void pipeline_planner::PipelinePlanner::setPipeRadius | ( | float | radius | ) |
substitute pipe_radius_ value when it is called from dynamic reconfigure
Definition at line 216 of file ppplanner_core.cpp.
|
inline |
Definition at line 138 of file ppplanner.h.
|
inline |
Definition at line 146 of file ppplanner.h.
|
inline |
Definition at line 150 of file ppplanner.h.
|
inline |
Definition at line 128 of file ppplanner.h.
|
private |
To make local goal on torch model.
| start | The start pose |
| goal | The goal pose |
| local_goal | The local goal calculated by the function |
| err | Error code 0: no error 1: use_torch is not used 2: start position is out of pipeline 3: goal position is out of pipeline 4: the length of a pipesegment is too short 5: unexpected error, torch area might be too narrow with respect to the pipeline radius 6: start point is out of torch area |
Definition at line 2259 of file ppplanner_core.cpp.
|
private |
Taking pipline radius in a given pipeline segment.
| contained_radius | Contained value of the radius. If it is 0.0 we use pipe_radius_ as a segment radius. |
Definition at line 2426 of file ppplanner_core.cpp.
|
private |
Definition at line 2437 of file ppplanner_core.cpp.
|
private |
Display consumed time on makePlan function.
| time_display | whether it will be displayed on terminal or not |
| duration | Duration time |
Definition at line 2247 of file ppplanner_core.cpp.
|
private |
To veil costmap other than that in pipeline segments.
| segids | IDs for pipe segments to use |
| startindex | Index for start pipe segment |
| goalindex | Index for goal pipe segment |
| start | Start point or current robot point |
Definition at line 1528 of file ppplanner_core.cpp.
|
private |
To veil costmap other than that in pipeline segments.
| segids | IDs for pipe segments to use |
| startindex | Index for start pipe segment |
| goalindex | Index for goal pipe segment |
| start | Start point or current robot point |
Definition at line 1701 of file ppplanner_core.cpp.
|
private |
To know the position of a robot in a pipe segment.
| pose | The pose of the robot |
| id | The ID for a pipe segment |
| part | Which part in a segment. 1: in the pipe segment 2: in the start circle 3: in the end circle 0: others, especially for errors or out of the pipe segment area |
| dist | Distance to indicate the position |
Definition at line 1440 of file ppplanner_core.cpp.
|
private |
Definition at line 540 of file ppplanner.h.
|
private |
Definition at line 556 of file ppplanner.h.
|
private |
Definition at line 505 of file ppplanner.h.
|
private |
Definition at line 562 of file ppplanner.h.
|
private |
Definition at line 504 of file ppplanner.h.
|
private |
Definition at line 573 of file ppplanner.h.
|
private |
Definition at line 375 of file ppplanner.h.
|
private |
Definition at line 377 of file ppplanner.h.
|
private |
Definition at line 558 of file ppplanner.h.
|
private |
Definition at line 503 of file ppplanner.h.
|
private |
Definition at line 546 of file ppplanner.h.
|
private |
Definition at line 547 of file ppplanner.h.
|
private |
Definition at line 502 of file ppplanner.h.
|
private |
Definition at line 548 of file ppplanner.h.
|
private |
Definition at line 539 of file ppplanner.h.
|
private |
Definition at line 565 of file ppplanner.h.
|
private |
Definition at line 514 of file ppplanner.h.
|
private |
Definition at line 513 of file ppplanner.h.
|
private |
Definition at line 512 of file ppplanner.h.
|
private |
Definition at line 597 of file ppplanner.h.
|
private |
Definition at line 542 of file ppplanner.h.
|
private |
Definition at line 537 of file ppplanner.h.
|
private |
Definition at line 506 of file ppplanner.h.
|
private |
Definition at line 535 of file ppplanner.h.
|
private |
Definition at line 536 of file ppplanner.h.
|
private |
Definition at line 533 of file ppplanner.h.
|
private |
Definition at line 531 of file ppplanner.h.
|
private |
Definition at line 534 of file ppplanner.h.
|
private |
Definition at line 532 of file ppplanner.h.
|
private |
Definition at line 567 of file ppplanner.h.
|
private |
Definition at line 544 of file ppplanner.h.
|
private |
Definition at line 520 of file ppplanner.h.
|
private |
Definition at line 549 of file ppplanner.h.
|
private |
Definition at line 564 of file ppplanner.h.
|
private |
Definition at line 545 of file ppplanner.h.
|
private |
Definition at line 530 of file ppplanner.h.
|
private |
Definition at line 508 of file ppplanner.h.
|
private |
Definition at line 507 of file ppplanner.h.
|
private |
Definition at line 550 of file ppplanner.h.
|
private |
Definition at line 551 of file ppplanner.h.
|
private |
Definition at line 568 of file ppplanner.h.
|
private |
Definition at line 510 of file ppplanner.h.
|
private |
Definition at line 552 of file ppplanner.h.
|
private |
Definition at line 560 of file ppplanner.h.
|
private |
Definition at line 543 of file ppplanner.h.
|
private |
Definition at line 571 of file ppplanner.h.
|
private |
Definition at line 571 of file ppplanner.h.
|
private |
Definition at line 555 of file ppplanner.h.
|
private |
Definition at line 570 of file ppplanner.h.
|
private |
Definition at line 561 of file ppplanner.h.