#include <start_pose_predictor.h>
|
bool | buildResults (const trajectory_tracker::Path2D::ConstIterator &expected_start_pose_it, const geometry_msgs::Pose &start_metric, const GridAstar< 3, 2 >::Gridmap< char, 0x40 > &cm, Astar::Vec &start_grid) |
|
trajectory_tracker::Path2D::ConstIterator | getExpectedPose (const std::vector< double > &etas) const |
|
double | getInitialETA (const geometry_msgs::Pose &robot_pose, const trajectory_tracker::Pose2D &initial_path_pose) const |
|
trajectory_tracker::Path2D::ConstIterator | getSwitchBack (const std::vector< double > &etas) const |
|
bool | isGridCenter (const trajectory_tracker::Pose2D &pose) const |
|
bool | isPathColliding (const trajectory_tracker::Path2D::ConstIterator &begin, const trajectory_tracker::Path2D::ConstIterator &end, const GridAstar< 3, 2 >::Gridmap< char, 0x40 > &cm) |
|
bool | removeAlreadyPassed (const geometry_msgs::Pose &robot_pose) |
|
Definition at line 47 of file start_pose_predictor.h.
◆ Astar
◆ buildResults()
◆ clear()
void planner_cspace::planner_3d::StartPosePredictor::clear |
( |
| ) |
|
◆ getExpectedPose()
◆ getInitialETA()
◆ getPreservedPath()
const nav_msgs::Path& planner_cspace::planner_3d::StartPosePredictor::getPreservedPath |
( |
| ) |
const |
|
inline |
◆ getPreservedPathLength()
const double planner_cspace::planner_3d::StartPosePredictor::getPreservedPathLength |
( |
| ) |
const |
|
inline |
◆ getSwitchBack()
◆ isGridCenter()
◆ isPathColliding()
◆ process()
bool planner_cspace::planner_3d::StartPosePredictor::process |
( |
const geometry_msgs::Pose & |
robot_pose, |
|
|
const GridAstar< 3, 2 >::Gridmap< char, 0x40 > & |
cm, |
|
|
const costmap_cspace_msgs::MapMetaData3D & |
map_info, |
|
|
const nav_msgs::Path & |
previous_path_msg, |
|
|
Astar::Vec & |
result_start_grid |
|
) |
| |
◆ removeAlreadyPassed()
bool planner_cspace::planner_3d::StartPosePredictor::removeAlreadyPassed |
( |
const geometry_msgs::Pose & |
robot_pose | ) |
|
|
private |
◆ setConfig()
void planner_cspace::planner_3d::StartPosePredictor::setConfig |
( |
const Config & |
config | ) |
|
|
inline |
◆ config_
Config planner_cspace::planner_3d::StartPosePredictor::config_ |
|
private |
◆ map_info_
costmap_cspace_msgs::MapMetaData3D planner_cspace::planner_3d::StartPosePredictor::map_info_ |
|
private |
◆ preserved_path_
nav_msgs::Path planner_cspace::planner_3d::StartPosePredictor::preserved_path_ |
|
private |
◆ preserved_path_length_
double planner_cspace::planner_3d::StartPosePredictor::preserved_path_length_ = 0.0 |
|
private |
◆ previous_path_2d_
The documentation for this class was generated from the following files: