17 #include "nav2_mppi_controller/controller.hpp"
18 #include "nav2_mppi_controller/tools/utils.hpp"
22 namespace nav2_mppi_controller
26 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
27 std::string name,
const std::shared_ptr<tf2_ros::Buffer> tf,
28 const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
31 costmap_ros_ = costmap_ros;
34 parameters_handler_ = std::make_unique<ParametersHandler>(parent, name_);
36 auto node = parent_.lock();
38 auto getParam = parameters_handler_->getParamGetter(name_);
39 getParam(visualize_,
"visualize",
false);
41 getParam(publish_optimal_trajectory_,
"publish_optimal_trajectory",
false);
44 optimizer_.
initialize(parent_, name_, costmap_ros_, parameters_handler_.get());
45 path_handler_.
initialize(parent_, name_, costmap_ros_, tf_buffer_, parameters_handler_.get());
48 costmap_ros_->getGlobalFrameID(), parameters_handler_.get());
50 if (publish_optimal_trajectory_) {
51 opt_traj_pub_ = node->create_publisher<nav2_msgs::msg::Trajectory>(
52 "~/optimal_trajectory", rclcpp::SystemDefaultsQoS());
55 RCLCPP_INFO(logger_,
"Configured MPPI Controller: %s", name_.c_str());
62 parameters_handler_.reset();
63 opt_traj_pub_.reset();
64 RCLCPP_INFO(logger_,
"Cleaned up MPPI Controller: %s", name_.c_str());
69 auto node = parent_.lock();
71 parameters_handler_->start();
73 opt_traj_pub_->on_activate();
75 RCLCPP_INFO(logger_,
"Activated MPPI Controller: %s", name_.c_str());
82 opt_traj_pub_->on_deactivate();
84 RCLCPP_INFO(logger_,
"Deactivated MPPI Controller: %s", name_.c_str());
89 optimizer_.
reset(
false );
93 const geometry_msgs::msg::PoseStamped & robot_pose,
94 const geometry_msgs::msg::Twist & robot_speed,
97 #ifdef BENCHMARK_TESTING
98 auto start = std::chrono::system_clock::now();
101 std::lock_guard<std::mutex> param_lock(*parameters_handler_->getLock());
102 geometry_msgs::msg::Pose goal = path_handler_.
getTransformedGoal(robot_pose.header.stamp).pose;
104 nav_msgs::msg::Path transformed_plan = path_handler_.
transformPath(robot_pose);
107 std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> costmap_lock(*(costmap->getMutex()));
109 geometry_msgs::msg::TwistStamped cmd =
110 optimizer_.
evalControl(robot_pose, robot_speed, transformed_plan, goal, goal_checker);
112 #ifdef BENCHMARK_TESTING
113 auto end = std::chrono::system_clock::now();
114 auto duration = std::chrono::duration_cast<std::chrono::milliseconds>(end - start).count();
115 RCLCPP_INFO(logger_,
"Control loop execution time: %ld [ms]", duration);
118 Eigen::ArrayXXf optimal_trajectory;
119 if (publish_optimal_trajectory_ && opt_traj_pub_->get_subscription_count() > 0) {
121 auto trajectory_msg = utils::toTrajectoryMsg(
126 opt_traj_pub_->publish(std::move(trajectory_msg));
130 visualize(std::move(transformed_plan), cmd.header.stamp, optimal_trajectory);
137 nav_msgs::msg::Path transformed_plan,
138 const builtin_interfaces::msg::Time & cmd_stamp,
139 const Eigen::ArrayXXf & optimal_trajectory)
142 if (optimal_trajectory.size() > 0) {
143 trajectory_visualizer_.
add(optimal_trajectory,
"Optimal Trajectory", cmd_stamp);
145 trajectory_visualizer_.
add(
148 trajectory_visualizer_.
visualize(std::move(transformed_plan));
163 #include "pluginlib/class_list_macros.hpp"
geometry_msgs::msg::TwistStamped evalControl(const geometry_msgs::msg::PoseStamped &robot_pose, const geometry_msgs::msg::Twist &robot_speed, const nav_msgs::msg::Path &plan, const geometry_msgs::msg::Pose &goal, nav2_core::GoalChecker *goal_checker)
Compute control using MPPI algorithm.
const models::ControlSequence & getOptimalControlSequence()
Get the optimal control sequence for a cycle for visualization.
Eigen::ArrayXXf getOptimizedTrajectory()
Get the optimal trajectory for a cycle for visualization.
void reset(bool reset_dynamic_speed_limits=true)
Reset the optimization problem to initial conditions.
const models::OptimizerSettings & getSettings() const
Get the motion model time step.
models::Trajectories & getGeneratedTrajectories()
Get the trajectories generated in a cycle for visualization.
void shutdown()
Shutdown for optimizer at process end.
void setSpeedLimit(double speed_limit, bool percentage)
Set the maximum speed based on the speed limits callback.
void initialize(rclcpp_lifecycle::LifecycleNode::WeakPtr parent, const std::string &name, std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros, ParametersHandler *dynamic_parameters_handler)
Initializes optimizer on startup.
void setPath(const nav_msgs::msg::Path &plan)
Set new reference path.
geometry_msgs::msg::PoseStamped getTransformedGoal(const builtin_interfaces::msg::Time &stamp)
Get the global goal pose transformed to the local frame.
void initialize(rclcpp_lifecycle::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.
nav_msgs::msg::Path transformPath(const geometry_msgs::msg::PoseStamped &robot_pose)
transform global plan to local applying constraints, then prune global plan
void add(const Eigen::ArrayXXf &trajectory, const std::string &marker_namespace, const builtin_interfaces::msg::Time &cmd_stamp)
Add an optimal trajectory to visualize.
void visualize(const nav_msgs::msg::Path &plan)
Visualize the plan.
void on_deactivate()
Deactivate object.
void on_configure(rclcpp_lifecycle::LifecycleNode::WeakPtr parent, const std::string &name, const std::string &frame_id, ParametersHandler *parameters_handler)
Configure trajectory visualizer.
void on_activate()
Activate object.
void on_cleanup()
Cleanup object on shutdown.
controller interface that acts as a virtual base class for all controller plugins
Function-object for checking whether a goal has been reached.
A 2D costmap provides a mapping between points in the world and their associated "costs".
void cleanup() override
Cleanup resources.
geometry_msgs::msg::TwistStamped computeVelocityCommands(const geometry_msgs::msg::PoseStamped &robot_pose, const geometry_msgs::msg::Twist &robot_speed, nav2_core::GoalChecker *goal_checker) override
Main method to compute velocities using the optimizer.
void setPlan(const nav_msgs::msg::Path &path) override
Set new reference path to track.
void configure(const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, std::string name, const std::shared_ptr< tf2_ros::Buffer > tf, const std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros) override
Configure controller on bringup.
void setSpeedLimit(const double &speed_limit, const bool &percentage) override
Set new speed limit from callback.
void visualize(nav_msgs::msg::Path transformed_plan, const builtin_interfaces::msg::Time &cmd_stamp, const Eigen::ArrayXXf &optimal_trajectory)
Visualize trajectories.
void activate() override
Activate controller.
void reset() override
Reset the controller state between tasks.
void deactivate() override
Deactivate controller.