Go to the documentation of this file.
30 #ifndef PLANNER_CSPACE_PLANNER_3D_START_POSE_PREDICTOR_H
31 #define PLANNER_CSPACE_PLANNER_3D_START_POSE_PREDICTOR_H
35 #include <nav_msgs/Path.h>
37 #include <costmap_cspace_msgs/CSpace3D.h>
65 bool process(
const geometry_msgs::Pose& robot_pose,
67 const costmap_cspace_msgs::MapMetaData3D& map_info,
68 const nav_msgs::Path& previous_path_msg,
85 const geometry_msgs::Pose& start_metric,
105 #endif // PLANNER_CSPACE_PLANNER_3D_START_POSE_PREDICTOR_H
trajectory_tracker::Path2D::ConstIterator getExpectedPose(const std::vector< double > &etas) const
bool isGridCenter(const trajectory_tracker::Pose2D &pose) const
std::vector< Pose2D >::const_iterator ConstIterator
double getInitialETA(const geometry_msgs::Pose &robot_pose, const trajectory_tracker::Pose2D &initial_path_pose) const
double preserved_path_length_
double switch_back_prediction_sec_
bool 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)
trajectory_tracker::Path2D previous_path_2d_
bool removeAlreadyPassed(const geometry_msgs::Pose &robot_pose)
void setConfig(const Config &config)
costmap_cspace_msgs::MapMetaData3D map_info_
trajectory_tracker::Path2D::ConstIterator getSwitchBack(const std::vector< double > &etas) const
bool isPathColliding(const trajectory_tracker::Path2D::ConstIterator &begin, const trajectory_tracker::Path2D::ConstIterator &end, const GridAstar< 3, 2 >::Gridmap< char, 0x40 > &cm)
nav_msgs::Path preserved_path_
const nav_msgs::Path & getPreservedPath() const
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)
const double getPreservedPathLength() const
planner_cspace
Author(s): Atsushi Watanabe
autogenerated on Fri May 16 2025 02:15:23