start_pose_predictor.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2023, the neonavigation authors
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #ifndef PLANNER_CSPACE_PLANNER_3D_START_POSE_PREDICTOR_H
31 #define PLANNER_CSPACE_PLANNER_3D_START_POSE_PREDICTOR_H
32 
33 #include <vector>
34 
35 #include <nav_msgs/Path.h>
36 
37 #include <costmap_cspace_msgs/CSpace3D.h>
41 
42 namespace planner_cspace
43 {
44 namespace planner_3d
45 {
46 
48 {
49 public:
51 
52  struct Config
53  {
56  double dist_stop_;
57  double lin_vel_;
58  double ang_vel_;
59  };
60  void setConfig(const Config& config)
61  {
62  config_ = config;
63  clear();
64  }
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,
69  Astar::Vec& result_start_grid);
70  void clear();
71  const nav_msgs::Path& getPreservedPath() const
72  {
73  return preserved_path_;
74  }
75  const double getPreservedPathLength() const
76  {
78  }
79 
80 private:
81  bool removeAlreadyPassed(const geometry_msgs::Pose& robot_pose);
82  double getInitialETA(
83  const geometry_msgs::Pose& robot_pose, const trajectory_tracker::Pose2D& initial_path_pose) const;
84  bool buildResults(const trajectory_tracker::Path2D::ConstIterator& expected_start_pose_it,
85  const geometry_msgs::Pose& start_metric,
87  Astar::Vec& start_grid);
88  bool isGridCenter(const trajectory_tracker::Pose2D& pose) const;
92  trajectory_tracker::Path2D::ConstIterator getSwitchBack(const std::vector<double>& etas) const;
93  trajectory_tracker::Path2D::ConstIterator getExpectedPose(const std::vector<double>& etas) const;
94 
96  costmap_cspace_msgs::MapMetaData3D map_info_;
98  nav_msgs::Path preserved_path_;
99  double preserved_path_length_ = 0.0;
100 };
101 
102 } // namespace planner_3d
103 } // namespace planner_cspace
104 
105 #endif // PLANNER_CSPACE_PLANNER_3D_START_POSE_PREDICTOR_H
planner_cspace::planner_3d::StartPosePredictor::clear
void clear()
Definition: start_pose_predictor.cpp:76
planner_cspace
Definition: bbf.h:33
planner_cspace::planner_3d::StartPosePredictor
Definition: start_pose_predictor.h:47
planner_cspace::planner_3d::StartPosePredictor::getExpectedPose
trajectory_tracker::Path2D::ConstIterator getExpectedPose(const std::vector< double > &etas) const
Definition: start_pose_predictor.cpp:230
path2d.h
trajectory_tracker::Pose2D
planner_cspace::planner_3d::StartPosePredictor::isGridCenter
bool isGridCenter(const trajectory_tracker::Pose2D &pose) const
Definition: start_pose_predictor.cpp:165
trajectory_tracker::Path2D
grid_metric_converter.h
trajectory_tracker::Path2D::ConstIterator
std::vector< Pose2D >::const_iterator ConstIterator
planner_cspace::planner_3d::StartPosePredictor::getInitialETA
double getInitialETA(const geometry_msgs::Pose &robot_pose, const trajectory_tracker::Pose2D &initial_path_pose) const
Definition: start_pose_predictor.cpp:122
planner_cspace::planner_3d::StartPosePredictor::config_
Config config_
Definition: start_pose_predictor.h:95
planner_cspace::planner_3d::StartPosePredictor::preserved_path_length_
double preserved_path_length_
Definition: start_pose_predictor.h:99
planner_cspace::GridAstar< 3, 2 >
planner_cspace::planner_3d::StartPosePredictor::Config::switch_back_prediction_sec_
double switch_back_prediction_sec_
Definition: start_pose_predictor.h:55
planner_cspace::planner_3d::StartPosePredictor::Config::prediction_sec_
double prediction_sec_
Definition: start_pose_predictor.h:54
planner_cspace::planner_3d::StartPosePredictor::process
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)
Definition: start_pose_predictor.cpp:42
planner_cspace::planner_3d::StartPosePredictor::previous_path_2d_
trajectory_tracker::Path2D previous_path_2d_
Definition: start_pose_predictor.h:97
planner_cspace::planner_3d::StartPosePredictor::removeAlreadyPassed
bool removeAlreadyPassed(const geometry_msgs::Pose &robot_pose)
Definition: start_pose_predictor.cpp:83
planner_cspace::planner_3d::StartPosePredictor::Config::lin_vel_
double lin_vel_
Definition: start_pose_predictor.h:57
planner_cspace::planner_3d::StartPosePredictor::setConfig
void setConfig(const Config &config)
Definition: start_pose_predictor.h:60
planner_cspace::planner_3d::StartPosePredictor::map_info_
costmap_cspace_msgs::MapMetaData3D map_info_
Definition: start_pose_predictor.h:96
grid_astar.h
planner_cspace::planner_3d::StartPosePredictor::getSwitchBack
trajectory_tracker::Path2D::ConstIterator getSwitchBack(const std::vector< double > &etas) const
Definition: start_pose_predictor.cpp:194
planner_cspace::planner_3d::StartPosePredictor::Config::ang_vel_
double ang_vel_
Definition: start_pose_predictor.h:58
planner_cspace::planner_3d::StartPosePredictor::isPathColliding
bool isPathColliding(const trajectory_tracker::Path2D::ConstIterator &begin, const trajectory_tracker::Path2D::ConstIterator &end, const GridAstar< 3, 2 >::Gridmap< char, 0x40 > &cm)
Definition: start_pose_predictor.cpp:176
planner_cspace::planner_3d::StartPosePredictor::Config
Definition: start_pose_predictor.h:52
planner_cspace::planner_3d::StartPosePredictor::preserved_path_
nav_msgs::Path preserved_path_
Definition: start_pose_predictor.h:98
planner_cspace::planner_3d::StartPosePredictor::getPreservedPath
const nav_msgs::Path & getPreservedPath() const
Definition: start_pose_predictor.h:71
planner_cspace::planner_3d::StartPosePredictor::buildResults
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)
Definition: start_pose_predictor.cpp:132
planner_cspace::planner_3d::StartPosePredictor::Config::dist_stop_
double dist_stop_
Definition: start_pose_predictor.h:56
planner_cspace::CyclicVecBase
Definition: cyclic_vec.h:78
planner_cspace::planner_3d::StartPosePredictor::getPreservedPathLength
const double getPreservedPathLength() const
Definition: start_pose_predictor.h:75


planner_cspace
Author(s): Atsushi Watanabe
autogenerated on Fri May 16 2025 02:15:23