17 #ifndef NAV2_MPPI_CONTROLLER__TOOLS__PATH_HANDLER_HPP_
18 #define NAV2_MPPI_CONTROLLER__TOOLS__PATH_HANDLER_HPP_
25 #include "nav2_ros_common/lifecycle_node.hpp"
26 #include "tf2_ros/buffer.hpp"
27 #include "geometry_msgs/msg/pose_stamped.hpp"
28 #include "nav_msgs/msg/path.hpp"
29 #include "builtin_interfaces/msg/time.hpp"
30 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
31 #include "nav2_util/geometry_utils.hpp"
32 #include "nav2_core/controller_exceptions.hpp"
34 #include "nav2_mppi_controller/tools/parameters_handler.hpp"
39 using PathIterator = std::vector<geometry_msgs::msg::PoseStamped>::iterator;
40 using PathRange = std::pair<PathIterator, PathIterator>;
69 nav2::LifecycleNode::WeakPtr parent,
const std::string & name,
70 std::shared_ptr<nav2_costmap_2d::Costmap2DROS>,
77 void setPath(
const nav_msgs::msg::Path & plan);
83 nav_msgs::msg::Path &
getPath();
91 nav_msgs::msg::Path
transformPath(
const geometry_msgs::msg::PoseStamped & robot_pose);
98 geometry_msgs::msg::PoseStamped
getTransformedGoal(
const builtin_interfaces::msg::Time & stamp);
112 geometry_msgs::msg::PoseStamped
122 const geometry_msgs::msg::PoseStamped & global_pose);
129 void prunePlan(nav_msgs::msg::Path & plan,
const PathIterator end);
139 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_;
140 std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
143 nav_msgs::msg::Path global_plan_;
144 nav_msgs::msg::Path global_plan_up_to_inversion_;
145 rclcpp::Logger logger_{rclcpp::get_logger(
"MPPIController")};
147 double max_robot_pose_search_dist_{0};
148 double prune_distance_{0};
149 double transform_tolerance_{0};
150 float inversion_xy_tolerance_{0.2};
151 float inversion_yaw_tolerance{0.4};
152 bool enforce_path_inversion_{
false};
153 unsigned int inversion_locale_{0u};
Handles getting parameters and dynamic parameter changes.
Manager of incoming reference paths for transformation and processing.
bool isWithinInversionTolerances(const geometry_msgs::msg::PoseStamped &robot_pose)
Check if the robot pose is within the set inversion tolerances.
std::pair< nav_msgs::msg::Path, PathIterator > getGlobalPlanConsideringBoundsInCostmapFrame(const geometry_msgs::msg::PoseStamped &global_pose)
Get global plan within window of the local costmap size.
nav_msgs::msg::Path & getPath()
Get reference path.
void setPath(const nav_msgs::msg::Path &plan)
Set new reference path.
double getMaxCostmapDist()
Get largest dimension of costmap (radially)
void initialize(nav2::LifecycleNode::WeakPtr parent, const std::string &name, std::shared_ptr< nav2_costmap_2d::Costmap2DROS >, std::shared_ptr< tf2_ros::Buffer >, ParametersHandler *)
Initialize path handler on bringup.
geometry_msgs::msg::PoseStamped getTransformedGoal(const builtin_interfaces::msg::Time &stamp)
Get the global goal pose transformed to the local frame.
PathHandler()=default
Constructor for mppi::PathHandler.
~PathHandler()=default
Destructor for mppi::PathHandler.
void prunePlan(nav_msgs::msg::Path &plan, const PathIterator end)
Prune a path to only interesting portions.
nav_msgs::msg::Path transformPath(const geometry_msgs::msg::PoseStamped &robot_pose)
transform global plan to local applying constraints, then prune global plan
geometry_msgs::msg::PoseStamped transformToGlobalPlanFrame(const geometry_msgs::msg::PoseStamped &pose)
Transform a pose to the global reference frame.