Nav2 Navigation Stack - kilted  kilted
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, name_);
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  getParam(publish_optimal_trajectory_, "publish_optimal_trajectory", false);
42 
43  // Configure composed objects
44  optimizer_.initialize(parent_, name_, costmap_ros_, parameters_handler_.get());
45  path_handler_.initialize(parent_, name_, costmap_ros_, tf_buffer_, parameters_handler_.get());
46  trajectory_visualizer_.on_configure(
47  parent_, name_,
48  costmap_ros_->getGlobalFrameID(), parameters_handler_.get());
49 
50  if (publish_optimal_trajectory_) {
51  opt_traj_pub_ = node->create_publisher<nav2_msgs::msg::Trajectory>(
52  "~/optimal_trajectory", rclcpp::SystemDefaultsQoS());
53  }
54 
55  RCLCPP_INFO(logger_, "Configured MPPI Controller: %s", name_.c_str());
56 }
57 
59 {
60  optimizer_.shutdown();
61  trajectory_visualizer_.on_cleanup();
62  parameters_handler_.reset();
63  opt_traj_pub_.reset();
64  RCLCPP_INFO(logger_, "Cleaned up MPPI Controller: %s", name_.c_str());
65 }
66 
68 {
69  auto node = parent_.lock();
70  trajectory_visualizer_.on_activate();
71  parameters_handler_->start();
72  if (opt_traj_pub_) {
73  opt_traj_pub_->on_activate();
74  }
75  RCLCPP_INFO(logger_, "Activated MPPI Controller: %s", name_.c_str());
76 }
77 
79 {
80  trajectory_visualizer_.on_deactivate();
81  if (opt_traj_pub_) {
82  opt_traj_pub_->on_deactivate();
83  }
84  RCLCPP_INFO(logger_, "Deactivated MPPI Controller: %s", name_.c_str());
85 }
86 
88 {
89  optimizer_.reset(false /*Don't reset zone-based speed limits between requests*/);
90 }
91 
92 geometry_msgs::msg::TwistStamped MPPIController::computeVelocityCommands(
93  const geometry_msgs::msg::PoseStamped & robot_pose,
94  const geometry_msgs::msg::Twist & robot_speed,
95  nav2_core::GoalChecker * goal_checker)
96 {
97 #ifdef BENCHMARK_TESTING
98  auto start = std::chrono::system_clock::now();
99 #endif
100 
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;
103 
104  nav_msgs::msg::Path transformed_plan = path_handler_.transformPath(robot_pose);
105 
106  nav2_costmap_2d::Costmap2D * costmap = costmap_ros_->getCostmap();
107  std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> costmap_lock(*(costmap->getMutex()));
108 
109  geometry_msgs::msg::TwistStamped cmd =
110  optimizer_.evalControl(robot_pose, robot_speed, transformed_plan, goal, goal_checker);
111 
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);
116 #endif
117 
118  Eigen::ArrayXXf optimal_trajectory;
119  if (publish_optimal_trajectory_ && opt_traj_pub_->get_subscription_count() > 0) {
120  optimal_trajectory = optimizer_.getOptimizedTrajectory();
121  auto trajectory_msg = utils::toTrajectoryMsg(
122  optimal_trajectory,
123  optimizer_.getOptimalControlSequence(),
124  optimizer_.getSettings().model_dt,
125  cmd.header);
126  opt_traj_pub_->publish(std::move(trajectory_msg));
127  }
128 
129  if (visualize_) {
130  visualize(std::move(transformed_plan), cmd.header.stamp, optimal_trajectory);
131  }
132 
133  return cmd;
134 }
135 
137  nav_msgs::msg::Path transformed_plan,
138  const builtin_interfaces::msg::Time & cmd_stamp,
139  const Eigen::ArrayXXf & optimal_trajectory)
140 {
141  trajectory_visualizer_.add(optimizer_.getGeneratedTrajectories(), "Candidate Trajectories");
142  if (optimal_trajectory.size() > 0) {
143  trajectory_visualizer_.add(optimal_trajectory, "Optimal Trajectory", cmd_stamp);
144  } else {
145  trajectory_visualizer_.add(
146  optimizer_.getOptimizedTrajectory(), "Optimal Trajectory", cmd_stamp);
147  }
148  trajectory_visualizer_.visualize(std::move(transformed_plan));
149 }
150 
151 void MPPIController::setPlan(const nav_msgs::msg::Path & path)
152 {
153  path_handler_.setPath(path);
154 }
155 
156 void MPPIController::setSpeedLimit(const double & speed_limit, const bool & percentage)
157 {
158  optimizer_.setSpeedLimit(speed_limit, percentage);
159 }
160 
161 } // namespace nav2_mppi_controller
162 
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.
Definition: optimizer.cpp:162
const models::ControlSequence & getOptimalControlSequence()
Get the optimal control sequence for a cycle for visualization.
Definition: optimizer.cpp:434
Eigen::ArrayXXf getOptimizedTrajectory()
Get the optimal trajectory for a cycle for visualization.
Definition: optimizer.cpp:416
void reset(bool reset_dynamic_speed_limits=true)
Reset the optimization problem to initial conditions.
Definition: optimizer.cpp:135
const models::OptimizerSettings & getSettings() const
Get the motion model time step.
Definition: optimizer.hpp:131
models::Trajectories & getGeneratedTrajectories()
Get the trajectories generated in a cycle for visualization.
Definition: optimizer.cpp:539
void shutdown()
Shutdown for optimizer at process end.
Definition: optimizer.cpp:54
void setSpeedLimit(double speed_limit, bool percentage)
Set the maximum speed based on the speed limits callback.
Definition: optimizer.cpp:512
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:32
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
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:69
void cleanup() override
Cleanup resources.
Definition: controller.cpp:58
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:92
void setPlan(const nav_msgs::msg::Path &path) override
Set new reference path to track.
Definition: controller.cpp:151
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:156
void visualize(nav_msgs::msg::Path transformed_plan, const builtin_interfaces::msg::Time &cmd_stamp, const Eigen::ArrayXXf &optimal_trajectory)
Visualize trajectories.
Definition: controller.cpp:136
void activate() override
Activate controller.
Definition: controller.cpp:67
void reset() override
Reset the controller state between tasks.
Definition: controller.cpp:87
void deactivate() override
Deactivate controller.
Definition: controller.cpp:78