Classes | Public Member Functions | Private Member Functions | Private Attributes | List of all members
pipeline_planner::PipelinePlanner Class Reference

Provides a global planner that will make a route along check points gained from topic. This planner uses global_planner. More...

#include <ppplanner.h>

Inheritance diagram for pipeline_planner::PipelinePlanner:
Inheritance graph
[legend]

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...
 

Private Attributes

double centre_weight_
 
bool charge_
 
std::vector< geometry_msgs::PoseStamped > check_points_
 
std_msgs::Float32 consumed_time_
 
costmap_2d::Costmap2Dcostmap_
 
bool debug
 
std::vector< double > dist_from_pipe_centre_
 
dynamic_reconfigure::Server< pipeline_planner::PipelinePlannerConfig > * dsrv_
 
bool fix_pipe_radius_
 
std::string gained_frame_id_
 
ros::ServiceServer get_checkpoints_srv_
 
ros::ServiceServer get_numof_checkpoints_srv_
 
bool initialized_
 
ros::ServiceServer inquire_segments_srv_
 
unsigned char lethal_cost_
 
boost::mutex mutex_robot_position_
 
std::string name_
 
costmap_2d::Costmap2Dnavfn_costmap_
 
navfn::NavfnROSnavfn_planner_
 
int num_threads_
 
int openclose_
 
double pipe_radius_
 
nav_msgs::OccupancyGrid pipeline_
 
ros::Publisher pub_initialised_
 
ros::Publisher pub_pipeline_
 
ros::Publisher pub_plan_
 
ros::Publisher pub_result_
 
ros::Publisher pub_robot_position_
 
ros::Publisher pub_status_
 
ros::Publisher pub_time_
 
ros::ServiceServer read_state_srv_
 
std_msgs::UInt32 read_status_
 
ros::ServiceServer receive_checkpoints_srv_
 
geometry_msgs::Pose robot_position_
 
ros::ServiceServer robot_state_srv_
 
std_msgs::UInt32 robot_status_
 
std::vector< pipeline_planner::SegmentInfo > segment_infos_
 
std::vector< double > segment_lengths_
 
ros::ServiceServer set_a_radius_srv_
 
ros::ServiceServer set_a_rightshift_srv_
 
ros::Subscriber sub_movebase_goal_
 
ros::Subscriber sub_robot_pose_
 
boost::thread * thread_robot_position_
 
bool time_display_
 
double tolerance_
 
double torch_area_x_
 
double torch_area_y_
 
bool use_straight_
 
bool use_torch_
 
bool willDisplay_
 

Additional Inherited Members

- Protected Member Functions inherited from nav_core::BaseGlobalPlanner
 BaseGlobalPlanner ()
 

Detailed Description

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.

Constructor & Destructor Documentation

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.

Parameters
nameThe name of this planner
costmapA 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.

Member Function Documentation

void pipeline_planner::PipelinePlanner::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 
)
private

To calculate the pipeline without GPU.

Definition at line 2117 of file ppplanner_core.cpp.

void pipeline_planner::PipelinePlanner::callbackgoal ( const move_base_msgs::MoveBaseActionGoal::ConstPtr &  goal)
private

Callback function for reception of actionlib goal.

Parameters
goalcallback message

Definition at line 2194 of file ppplanner_core.cpp.

void pipeline_planner::PipelinePlanner::callbackRobotPose ( const geometry_msgs::Pose::ConstPtr &  pose)
private

Callback function for reception of robot position.

Parameters
posecallback message

Definition at line 2198 of file ppplanner_core.cpp.

bool pipeline_planner::PipelinePlanner::ConnectPoints ( const geometry_msgs::PoseStamped &  start,
const geometry_msgs::PoseStamped &  goal,
const std::vector< int >  segids,
std::vector< geometry_msgs::PoseStamped > &  plan 
)
private

To substitute plan by connecting start point, checkpoints and goal point.

Parameters
startThe start pose
goalThe goal pose
segidsIDs for checkpoints to use
planThe plan, which will be filled by the function
Returns
True if valid plan is gained

Definition at line 1880 of file ppplanner_core.cpp.

int pipeline_planner::PipelinePlanner::costCheck ( int  endpoint)
private

To check received checkpoints whether it has a problem on costmap or not.

Parameters
endpointThe last point of received checkpoints sequence
Returns
values 1:The part of the route made by the check points is off the global costmap.(error) 2:The route includes an obstacle.(permitted) 0:The check points are received.(accepted)

Definition at line 450 of file ppplanner_core.cpp.

int pipeline_planner::PipelinePlanner::CrossTorchArea ( const double  tx,
const double  ty,
const double  sx,
const double  sy,
const double  ex,
const double  ey,
double &  bx,
double &  by 
)
private

Whether the line segment crosses the torch area boundary or not.

Parameters
txThe centre of torch area x
tyThe centre of torch area y
sxThe start of the line segment x
syThe start of the line segment y
exThe end of the line segment x
eyThe end of the line segment y
bxThe gained corss point x
byThe gained corss point y
Returns
0: segment is in the area 1: start point is out of area 2: start is in the area and end is out of area (cross) -1: error -2: the length of pipe segment is too short

Definition at line 2385 of file ppplanner_core.cpp.

bool pipeline_planner::PipelinePlanner::DistanceFromCentre ( int  endpoint)
private

Calculation of cell's distance from pipe centre.

Parameters
endpointThe last point of received checkpoints sequence
Returns
Always true

Definition at line 543 of file ppplanner_core.cpp.

bool pipeline_planner::PipelinePlanner::DistanceFromCentre_cuda ( int  endpoint)
private

Calculation of cell's distance from pipe centre.

Parameters
endpointThe last point of received checkpoints sequence
Returns
Always true

Definition at line 615 of file ppplanner_core.cpp.

bool pipeline_planner::PipelinePlanner::DrawOpenSegment ( const geometry_msgs::PoseStamped  init_point,
const geometry_msgs::PoseStamped  end_point,
std::vector< geometry_msgs::PoseStamped > &  plan 
)
private

To substitute the plan along two points.

Parameters
init_pointInitial point
end_pointEnd point
planThe plan, which will be filled by the function
Returns
Always true

Definition at line 1931 of file ppplanner_core.cpp.

bool pipeline_planner::PipelinePlanner::getCheckpoints ( pipeline_planner::GetCheckpoints::Request &  req,
pipeline_planner::GetCheckpoints::Response &  res 
)
inlineprivate

Get check points.

Parameters
reqDummy argument for input
resThe check points and the open close flag
Returns
Always true

Definition at line 205 of file ppplanner.h.

bool pipeline_planner::PipelinePlanner::getNumofCheckpoints ( pipeline_planner::GetNumofCheckpoints::Request &  req,
pipeline_planner::GetNumofCheckpoints::Response &  res 
)
inlineprivate

Get the status of reading checkpoints.

Parameters
reqDummy argument for input
resThe status of reading checkpoints for output
Returns
Always true

Definition at line 228 of file ppplanner.h.

bool pipeline_planner::PipelinePlanner::getReadStatus ( pipeline_planner::GetReadStatus::Request &  req,
pipeline_planner::GetReadStatus::Response &  res 
)
inlineprivate

Get the status of reading checkpoints.

Parameters
reqDummy argument for input
resThe status of reading checkpoints for output
Returns
Always true

Definition at line 183 of file ppplanner.h.

bool pipeline_planner::PipelinePlanner::getRobotStatus ( pipeline_planner::GetRobotStatus::Request &  req,
pipeline_planner::GetRobotStatus::Response &  res 
)
inlineprivate

Get the status of a robot.

Parameters
reqDummy argument for input
resThe status of a robot for output
Returns
Always true

Definition at line 194 of file ppplanner.h.

bool pipeline_planner::PipelinePlanner::hasNoCross ( const int  endpoint,
const std::vector< geometry_msgs::PoseStamped >  check_points 
)
private

To check whether a sequence of checkpoints has a crossing or not.

Parameters
endpointThe last point of checkpoints sequence. It depends on openclose flag.
check_pointsReceived checkpoints
Returns
True if the sequence of checkpoints doesn't have a crossing

Definition at line 377 of file ppplanner_core.cpp.

void pipeline_planner::PipelinePlanner::informRobotPose ( )
private

loop for informing the robot position by a thread

Definition at line 2205 of file ppplanner_core.cpp.

void pipeline_planner::PipelinePlanner::initialize ( std::string  name,
costmap_2d::Costmap2DROS costmap_ros 
)
virtual

Initialisation function for the Planner.

Parameters
nameThe name of this planner
costmap_rosA 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.

Parameters
nameThe name of this planner
costmapA pointer to the costmap
frame_idThe global frame of the costmap

Definition at line 120 of file ppplanner_core.cpp.

bool pipeline_planner::PipelinePlanner::InitSegInfo ( )
private

Initialisation of segment info.

Returns
False if one of the distances is too short It is supposed check points and open close flag was well @ received.

Definition at line 715 of file ppplanner_core.cpp.

bool pipeline_planner::PipelinePlanner::InPipeSegment ( const geometry_msgs::PoseStamped &  pose,
double  radius,
double  start_edge_radius,
double  end_edge_radius,
double  tolerance,
int  index 
)
private

Verification of whether the position is in the pipeline segment or not.

Parameters
poseThe position for verification
radiusThe radius of the pipeline
start_edge_radiusThe radius for start edge circle
end_edge_radiusThe radius for end edge circle
toleranceThe minimum value of the length of the pipeline segment
indexThe index of the pipeline segment
Returns
True if the position is in the pipeline segment

Definition at line 1282 of file ppplanner_core.cpp.

bool pipeline_planner::PipelinePlanner::InquireSegments ( pipeline_planner::InquireSegments::Request &  req,
pipeline_planner::InquireSegments::Response &  res 
)
private

Inquiring segments information.

Parameters
reqDummy argument for input
resThe information of segments
Returns
Always true

Definition at line 762 of file ppplanner_core.cpp.

bool pipeline_planner::PipelinePlanner::isBehindInaSegment ( int  idx,
const geometry_msgs::PoseStamped &  start,
const geometry_msgs::PoseStamped &  goal 
)
private

Whether the goal point is behind the start point in a pipe segment.

Parameters
idxIndex of the pipeline segment
startStart position
goalGoal position
Returns
True if the goal is behind the start

Definition at line 1500 of file ppplanner_core.cpp.

bool pipeline_planner::PipelinePlanner::knowRobotPosition ( const geometry_msgs::Pose  pose,
int &  ID,
double &  distance 
)
private

To know the position of a robot in the pipeline.

Parameters
poseThe position of the robot
IDID number for the pipesegment to which the robot belongs
distanceThe distance from start check point in the pipe segment to which the robot belongs
Returns
True if the robot is in a pipesegment

Definition at line 1328 of file ppplanner_core.cpp.

void pipeline_planner::PipelinePlanner::makePipeline ( )
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.

void pipeline_planner::PipelinePlanner::makePipeline ( bool  legal)
private

Definition at line 2000 of file ppplanner_core.cpp.

bool pipeline_planner::PipelinePlanner::makePlan ( const geometry_msgs::PoseStamped &  start,
const geometry_msgs::PoseStamped &  goal,
std::vector< geometry_msgs::PoseStamped > &  plan 
)
virtual

Given a goal pose in the world, compute a plan.

Parameters
startThe start pose
goalThe goal pose
planThe plan... filled by the planner
Returns
True if a valid plan was found, false otherwise

Implements nav_core::BaseGlobalPlanner.

Definition at line 986 of file ppplanner_core.cpp.

void pipeline_planner::PipelinePlanner::PublishCheckpointsResult ( std_msgs::UInt32  result)
private

Callback function for subscription of checkpoints data from topic.

Parameters
checkpointsCheckpoints 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
resultResult status

Definition at line 758 of file ppplanner_core.cpp.

void pipeline_planner::PipelinePlanner::publishPlan ( const std::vector< geometry_msgs::PoseStamped > &  path)
private

To publish a path.

Parameters
pathPath 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.

Parameters
reqCheckpoints for reception
resStatus of receiving checkpoints
Returns
Always true

Definition at line 778 of file ppplanner_core.cpp.

void pipeline_planner::PipelinePlanner::reconfigureCB ( pipeline_planner::PipelinePlannerConfig &  config,
uint32_t  level 
)
private

Callback function for dynamic reconfiguration.

Parameters
configThe new configuration
levelORing together level values of the parameters

Definition at line 203 of file ppplanner_core.cpp.

bool pipeline_planner::PipelinePlanner::SetARadius ( pipeline_planner::SetARadius::Request &  req,
pipeline_planner::SetARadius::Response &  res 
)
private

Service to set a pipeline segment radius.

Parameters
reqID and radius for new pipeline segment radius
resThe 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
Returns
always true

Definition at line 264 of file ppplanner_core.cpp.

bool pipeline_planner::PipelinePlanner::SetARightshift ( pipeline_planner::SetARightshift::Request &  req,
pipeline_planner::SetARightshift::Response &  res 
)
private

Service to set a right shift value for a pipeline segment.

Parameters
reqID and right shift value for the pipeline segment
resThe 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
Returns
always true

Definition at line 340 of file ppplanner_core.cpp.

void pipeline_planner::PipelinePlanner::setCharge ( bool  charge)
inline

Definition at line 142 of file ppplanner.h.

void pipeline_planner::PipelinePlanner::setLethal ( unsigned char  lethal_cost)
inline

Definition at line 124 of file ppplanner.h.

void pipeline_planner::PipelinePlanner::setNumThread ( float  num_threads)
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.

void pipeline_planner::PipelinePlanner::setStraight ( bool  use_straight)
inline

Definition at line 138 of file ppplanner.h.

void pipeline_planner::PipelinePlanner::setTimeDisplay ( bool  time_display)
inline

Definition at line 146 of file ppplanner.h.

void pipeline_planner::PipelinePlanner::setTorchArea ( bool  use_torch,
float  torch_area_x,
float  torch_area_y 
)
inline

Definition at line 150 of file ppplanner.h.

void pipeline_planner::PipelinePlanner::setWeight ( float  centre_weight)
inline

Definition at line 128 of file ppplanner.h.

bool pipeline_planner::PipelinePlanner::TakeLocalGoal ( const geometry_msgs::PoseStamped &  start,
const geometry_msgs::PoseStamped &  goal,
geometry_msgs::PoseStamped &  local_goal,
int &  err 
)
private

To make local goal on torch model.

Parameters
startThe start pose
goalThe goal pose
local_goalThe local goal calculated by the function
errError 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
Returns
True if there is no error we only use this function when we use torch model

Definition at line 2259 of file ppplanner_core.cpp.

double pipeline_planner::PipelinePlanner::TakeSegmentRadius ( const double  contained_radius)
private

Taking pipline radius in a given pipeline segment.

Parameters
contained_radiusContained value of the radius. If it is 0.0 we use pipe_radius_ as a segment radius.
Returns
Gained value

Definition at line 2426 of file ppplanner_core.cpp.

void pipeline_planner::PipelinePlanner::ThreadNumberAdjusment ( bool  debug)
private

Definition at line 2437 of file ppplanner_core.cpp.

void pipeline_planner::PipelinePlanner::TimeDisplay ( const bool  time_display,
const double  duration 
)
private

Display consumed time on makePlan function.

Parameters
time_displaywhether it will be displayed on terminal or not
durationDuration time

Definition at line 2247 of file ppplanner_core.cpp.

bool pipeline_planner::PipelinePlanner::VeilCostmap ( const std::vector< int >  segids,
const int  startindex,
const int  goalindex,
const geometry_msgs::PoseStamped &  start 
)
private

To veil costmap other than that in pipeline segments.

Parameters
segidsIDs for pipe segments to use
startindexIndex for start pipe segment
goalindexIndex for goal pipe segment
startStart point or current robot point
Returns
always True

Definition at line 1528 of file ppplanner_core.cpp.

bool pipeline_planner::PipelinePlanner::VeilCostmap_cuda ( const std::vector< int >  segids,
const int  startindex,
const int  goalindex,
const geometry_msgs::PoseStamped &  start 
)
private

To veil costmap other than that in pipeline segments.

Parameters
segidsIDs for pipe segments to use
startindexIndex for start pipe segment
goalindexIndex for goal pipe segment
startStart point or current robot point
Returns
always True

Definition at line 1701 of file ppplanner_core.cpp.

bool pipeline_planner::PipelinePlanner::whereInaPipeSegment ( const geometry_msgs::Pose  pose,
const int  id,
const double  radius,
const double  sradius,
const double  eradius,
int &  part,
double &  dist,
double  tolerance 
)
private

To know the position of a robot in a pipe segment.

Parameters
poseThe pose of the robot
idThe ID for a pipe segment
partWhich 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
distDistance to indicate the position
Returns
True if the robot is in the pipe segment

Definition at line 1440 of file ppplanner_core.cpp.

Member Data Documentation

double pipeline_planner::PipelinePlanner::centre_weight_
private

Definition at line 540 of file ppplanner.h.

bool pipeline_planner::PipelinePlanner::charge_
private

Definition at line 556 of file ppplanner.h.

std::vector<geometry_msgs::PoseStamped> pipeline_planner::PipelinePlanner::check_points_
private

Definition at line 505 of file ppplanner.h.

std_msgs::Float32 pipeline_planner::PipelinePlanner::consumed_time_
private

Definition at line 562 of file ppplanner.h.

costmap_2d::Costmap2D* pipeline_planner::PipelinePlanner::costmap_
private

Definition at line 504 of file ppplanner.h.

bool pipeline_planner::PipelinePlanner::debug
private

Definition at line 573 of file ppplanner.h.

std::vector<double> pipeline_planner::PipelinePlanner::dist_from_pipe_centre_
private

Definition at line 375 of file ppplanner.h.

dynamic_reconfigure::Server<pipeline_planner::PipelinePlannerConfig>* pipeline_planner::PipelinePlanner::dsrv_
private

Definition at line 377 of file ppplanner.h.

bool pipeline_planner::PipelinePlanner::fix_pipe_radius_
private

Definition at line 558 of file ppplanner.h.

std::string pipeline_planner::PipelinePlanner::gained_frame_id_
private

Definition at line 503 of file ppplanner.h.

ros::ServiceServer pipeline_planner::PipelinePlanner::get_checkpoints_srv_
private

Definition at line 546 of file ppplanner.h.

ros::ServiceServer pipeline_planner::PipelinePlanner::get_numof_checkpoints_srv_
private

Definition at line 547 of file ppplanner.h.

bool pipeline_planner::PipelinePlanner::initialized_
private

Definition at line 502 of file ppplanner.h.

ros::ServiceServer pipeline_planner::PipelinePlanner::inquire_segments_srv_
private

Definition at line 548 of file ppplanner.h.

unsigned char pipeline_planner::PipelinePlanner::lethal_cost_
private

Definition at line 539 of file ppplanner.h.

boost::mutex pipeline_planner::PipelinePlanner::mutex_robot_position_
private

Definition at line 565 of file ppplanner.h.

std::string pipeline_planner::PipelinePlanner::name_
private

Definition at line 514 of file ppplanner.h.

costmap_2d::Costmap2D* pipeline_planner::PipelinePlanner::navfn_costmap_
private

Definition at line 513 of file ppplanner.h.

navfn::NavfnROS* pipeline_planner::PipelinePlanner::navfn_planner_
private

Definition at line 512 of file ppplanner.h.

int pipeline_planner::PipelinePlanner::num_threads_
private

Definition at line 597 of file ppplanner.h.

int pipeline_planner::PipelinePlanner::openclose_
private

Definition at line 542 of file ppplanner.h.

double pipeline_planner::PipelinePlanner::pipe_radius_
private

Definition at line 537 of file ppplanner.h.

nav_msgs::OccupancyGrid pipeline_planner::PipelinePlanner::pipeline_
private

Definition at line 506 of file ppplanner.h.

ros::Publisher pipeline_planner::PipelinePlanner::pub_initialised_
private

Definition at line 535 of file ppplanner.h.

ros::Publisher pipeline_planner::PipelinePlanner::pub_pipeline_
private

Definition at line 536 of file ppplanner.h.

ros::Publisher pipeline_planner::PipelinePlanner::pub_plan_
private

Definition at line 533 of file ppplanner.h.

ros::Publisher pipeline_planner::PipelinePlanner::pub_result_
private

Definition at line 531 of file ppplanner.h.

ros::Publisher pipeline_planner::PipelinePlanner::pub_robot_position_
private

Definition at line 534 of file ppplanner.h.

ros::Publisher pipeline_planner::PipelinePlanner::pub_status_
private

Definition at line 532 of file ppplanner.h.

ros::Publisher pipeline_planner::PipelinePlanner::pub_time_
private

Definition at line 567 of file ppplanner.h.

ros::ServiceServer pipeline_planner::PipelinePlanner::read_state_srv_
private

Definition at line 544 of file ppplanner.h.

std_msgs::UInt32 pipeline_planner::PipelinePlanner::read_status_
private

Definition at line 520 of file ppplanner.h.

ros::ServiceServer pipeline_planner::PipelinePlanner::receive_checkpoints_srv_
private

Definition at line 549 of file ppplanner.h.

geometry_msgs::Pose pipeline_planner::PipelinePlanner::robot_position_
private

Definition at line 564 of file ppplanner.h.

ros::ServiceServer pipeline_planner::PipelinePlanner::robot_state_srv_
private

Definition at line 545 of file ppplanner.h.

std_msgs::UInt32 pipeline_planner::PipelinePlanner::robot_status_
private

Definition at line 530 of file ppplanner.h.

std::vector<pipeline_planner::SegmentInfo> pipeline_planner::PipelinePlanner::segment_infos_
private

Definition at line 508 of file ppplanner.h.

std::vector<double> pipeline_planner::PipelinePlanner::segment_lengths_
private

Definition at line 507 of file ppplanner.h.

ros::ServiceServer pipeline_planner::PipelinePlanner::set_a_radius_srv_
private

Definition at line 550 of file ppplanner.h.

ros::ServiceServer pipeline_planner::PipelinePlanner::set_a_rightshift_srv_
private

Definition at line 551 of file ppplanner.h.

ros::Subscriber pipeline_planner::PipelinePlanner::sub_movebase_goal_
private

Definition at line 568 of file ppplanner.h.

ros::Subscriber pipeline_planner::PipelinePlanner::sub_robot_pose_
private

Definition at line 510 of file ppplanner.h.

boost::thread* pipeline_planner::PipelinePlanner::thread_robot_position_
private

Definition at line 552 of file ppplanner.h.

bool pipeline_planner::PipelinePlanner::time_display_
private

Definition at line 560 of file ppplanner.h.

double pipeline_planner::PipelinePlanner::tolerance_
private

Definition at line 543 of file ppplanner.h.

double pipeline_planner::PipelinePlanner::torch_area_x_
private

Definition at line 571 of file ppplanner.h.

double pipeline_planner::PipelinePlanner::torch_area_y_
private

Definition at line 571 of file ppplanner.h.

bool pipeline_planner::PipelinePlanner::use_straight_
private

Definition at line 555 of file ppplanner.h.

bool pipeline_planner::PipelinePlanner::use_torch_
private

Definition at line 570 of file ppplanner.h.

bool pipeline_planner::PipelinePlanner::willDisplay_
private

Definition at line 561 of file ppplanner.h.


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


pipeline_planner
Author(s): seaos
autogenerated on Thu Jul 4 2019 19:55:39