Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
controller.cpp
1 // Copyright (c) 2022 Samsung Research America, @artofnothingness Alexey Budyakov
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include <stdint.h>
16 #include <chrono>
17 #include "nav2_mppi_controller/controller.hpp"
18 #include "nav2_mppi_controller/tools/utils.hpp"
19 
20 // #define BENCHMARK_TESTING
21 
22 namespace nav2_mppi_controller
23 {
24 
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)
29 {
30  parent_ = parent;
31  costmap_ros_ = costmap_ros;
32  tf_buffer_ = tf;
33  name_ = name;
34  parameters_handler_ = std::make_unique<ParametersHandler>(parent);
35 
36  auto node = parent_.lock();
37  // Get high-level controller parameters
38  auto getParam = parameters_handler_->getParamGetter(name_);
39  getParam(visualize_, "visualize", false);
40 
41  // Configure composed objects
42  optimizer_.initialize(parent_, name_, costmap_ros_, parameters_handler_.get());
43  path_handler_.initialize(parent_, name_, costmap_ros_, tf_buffer_, parameters_handler_.get());
44  trajectory_visualizer_.on_configure(
45  parent_, name_,
46  costmap_ros_->getGlobalFrameID(), parameters_handler_.get());
47 
48  RCLCPP_INFO(logger_, "Configured MPPI Controller: %s", name_.c_str());
49 }
50 
52 {
53  optimizer_.shutdown();
54  trajectory_visualizer_.on_cleanup();
55  parameters_handler_.reset();
56  RCLCPP_INFO(logger_, "Cleaned up MPPI Controller: %s", name_.c_str());
57 }
58 
60 {
61  trajectory_visualizer_.on_activate();
62  parameters_handler_->start();
63  RCLCPP_INFO(logger_, "Activated MPPI Controller: %s", name_.c_str());
64 }
65 
67 {
68  trajectory_visualizer_.on_deactivate();
69  RCLCPP_INFO(logger_, "Deactivated MPPI Controller: %s", name_.c_str());
70 }
71 
73 {
74  optimizer_.reset(false /*Don't reset zone-based speed limits between requests*/);
75 }
76 
77 geometry_msgs::msg::TwistStamped MPPIController::computeVelocityCommands(
78  const geometry_msgs::msg::PoseStamped & robot_pose,
79  const geometry_msgs::msg::Twist & robot_speed,
80  nav2_core::GoalChecker * goal_checker)
81 {
82 #ifdef BENCHMARK_TESTING
83  auto start = std::chrono::system_clock::now();
84 #endif
85 
86  std::lock_guard<std::mutex> param_lock(*parameters_handler_->getLock());
87  geometry_msgs::msg::Pose goal = path_handler_.getTransformedGoal(robot_pose.header.stamp).pose;
88 
89  nav_msgs::msg::Path transformed_plan = path_handler_.transformPath(robot_pose);
90 
91  nav2_costmap_2d::Costmap2D * costmap = costmap_ros_->getCostmap();
92  std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> costmap_lock(*(costmap->getMutex()));
93 
94  geometry_msgs::msg::TwistStamped cmd =
95  optimizer_.evalControl(robot_pose, robot_speed, transformed_plan, goal, goal_checker);
96 
97 #ifdef BENCHMARK_TESTING
98  auto end = std::chrono::system_clock::now();
99  auto duration = std::chrono::duration_cast<std::chrono::milliseconds>(end - start).count();
100  RCLCPP_INFO(logger_, "Control loop execution time: %ld [ms]", duration);
101 #endif
102 
103  if (visualize_) {
104  visualize(std::move(transformed_plan), cmd.header.stamp);
105  }
106 
107  return cmd;
108 }
109 
111  nav_msgs::msg::Path transformed_plan,
112  const builtin_interfaces::msg::Time & cmd_stamp)
113 {
114  trajectory_visualizer_.add(optimizer_.getGeneratedTrajectories(), "Candidate Trajectories");
115  trajectory_visualizer_.add(optimizer_.getOptimizedTrajectory(), "Optimal Trajectory", cmd_stamp);
116  trajectory_visualizer_.visualize(std::move(transformed_plan));
117 }
118 
119 void MPPIController::setPlan(const nav_msgs::msg::Path & path)
120 {
121  path_handler_.setPath(path);
122 }
123 
124 void MPPIController::setSpeedLimit(const double & speed_limit, const bool & percentage)
125 {
126  optimizer_.setSpeedLimit(speed_limit, percentage);
127 }
128 
129 } // namespace nav2_mppi_controller
130 
131 #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.
Definition: optimizer.cpp:164
void reset(bool reset_dynamic_speed_limits=true)
Reset the optimization problem to initial conditions.
Definition: optimizer.cpp:137
models::Trajectories & getGeneratedTrajectories()
Get the trajectories generated in a cycle for visualization.
Definition: optimizer.cpp:508
xt::xtensor< float, 2 > getOptimizedTrajectory()
Get the optimal trajectory for a cycle for visualization.
Definition: optimizer.cpp:395
void shutdown()
Shutdown for optimizer at process end.
Definition: optimizer.cpp:58
void setSpeedLimit(double speed_limit, bool percentage)
Set the maximum speed based on the speed limits callback.
Definition: optimizer.cpp:481
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.
Definition: optimizer.cpp:36
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 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 add(const xt::xtensor< float, 2 > &trajectory, const std::string &marker_namespace, const builtin_interfaces::msg::Time &cmd_stamp)
Add an optimal trajectory to visualize.
void on_cleanup()
Cleanup object on shutdown.
controller interface that acts as a virtual base class for all controller plugins
Definition: controller.hpp:61
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".
Definition: costmap_2d.hpp:68
void visualize(nav_msgs::msg::Path transformed_plan, const builtin_interfaces::msg::Time &cmd_stamp)
Visualize trajectories.
Definition: controller.cpp:110
void cleanup() override
Cleanup resources.
Definition: controller.cpp:51
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.
Definition: controller.cpp:77
void setPlan(const nav_msgs::msg::Path &path) override
Set new reference path to track.
Definition: controller.cpp:119
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.
Definition: controller.cpp:25
void setSpeedLimit(const double &speed_limit, const bool &percentage) override
Set new speed limit from callback.
Definition: controller.cpp:124
void activate() override
Activate controller.
Definition: controller.cpp:59
void reset() override
Reset the controller state between tasks.
Definition: controller.cpp:72
void deactivate() override
Deactivate controller.
Definition: controller.cpp:66