Nav2 Navigation Stack - humble  humble
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  clock_ = node->get_clock();
38  last_time_called_ = clock_->now();
39  // Get high-level controller parameters
40  auto getParam = parameters_handler_->getParamGetter(name_);
41  getParam(visualize_, "visualize", false);
42  getParam(reset_period_, "reset_period", 1.0);
43 
44  // Configure composed objects
45  optimizer_.initialize(parent_, name_, costmap_ros_, parameters_handler_.get());
46  path_handler_.initialize(parent_, name_, costmap_ros_, tf_buffer_, parameters_handler_.get());
47  trajectory_visualizer_.on_configure(
48  parent_, name_,
49  costmap_ros_->getGlobalFrameID(), parameters_handler_.get());
50 
51  RCLCPP_INFO(logger_, "Configured MPPI Controller: %s", name_.c_str());
52 }
53 
55 {
56  optimizer_.shutdown();
57  trajectory_visualizer_.on_cleanup();
58  parameters_handler_.reset();
59  RCLCPP_INFO(logger_, "Cleaned up MPPI Controller: %s", name_.c_str());
60 }
61 
63 {
64  trajectory_visualizer_.on_activate();
65  parameters_handler_->start();
66  RCLCPP_INFO(logger_, "Activated MPPI Controller: %s", name_.c_str());
67 }
68 
70 {
71  trajectory_visualizer_.on_deactivate();
72  RCLCPP_INFO(logger_, "Deactivated MPPI Controller: %s", name_.c_str());
73 }
74 
76 {
77  optimizer_.reset();
78 }
79 
80 geometry_msgs::msg::TwistStamped MPPIController::computeVelocityCommands(
81  const geometry_msgs::msg::PoseStamped & robot_pose,
82  const geometry_msgs::msg::Twist & robot_speed,
83  nav2_core::GoalChecker * goal_checker)
84 {
85 #ifdef BENCHMARK_TESTING
86  auto start = std::chrono::system_clock::now();
87 #endif
88 
89  if (clock_->now() - last_time_called_ > rclcpp::Duration::from_seconds(reset_period_)) {
90  reset();
91  }
92  last_time_called_ = clock_->now();
93 
94  std::lock_guard<std::mutex> param_lock(*parameters_handler_->getLock());
95  nav_msgs::msg::Path transformed_plan = path_handler_.transformPath(robot_pose);
96 
97  nav2_costmap_2d::Costmap2D * costmap = costmap_ros_->getCostmap();
98  std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> costmap_lock(*(costmap->getMutex()));
99 
100  geometry_msgs::msg::TwistStamped cmd =
101  optimizer_.evalControl(robot_pose, robot_speed, transformed_plan, goal_checker);
102 
103 #ifdef BENCHMARK_TESTING
104  auto end = std::chrono::system_clock::now();
105  auto duration = std::chrono::duration_cast<std::chrono::milliseconds>(end - start).count();
106  RCLCPP_INFO(logger_, "Control loop execution time: %ld [ms]", duration);
107 #endif
108 
109  if (visualize_) {
110  visualize(std::move(transformed_plan));
111  }
112 
113  return cmd;
114 }
115 
116 void MPPIController::visualize(nav_msgs::msg::Path transformed_plan)
117 {
118  trajectory_visualizer_.add(optimizer_.getGeneratedTrajectories(), "Candidate Trajectories");
119  trajectory_visualizer_.add(optimizer_.getOptimizedTrajectory(), "Optimal Trajectory");
120  trajectory_visualizer_.visualize(std::move(transformed_plan));
121 }
122 
123 void MPPIController::setPlan(const nav_msgs::msg::Path & path)
124 {
125  path_handler_.setPath(path);
126 }
127 
128 void MPPIController::setSpeedLimit(const double & speed_limit, const bool & percentage)
129 {
130  optimizer_.setSpeedLimit(speed_limit, percentage);
131 }
132 
133 } // namespace nav2_mppi_controller
134 
135 #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, nav2_core::GoalChecker *goal_checker)
Compute control using MPPI algorithm.
Definition: optimizer.cpp:134
models::Trajectories & getGeneratedTrajectories()
Get the trajectories generated in a cycle for visualization.
Definition: optimizer.cpp:449
xt::xtensor< float, 2 > getOptimizedTrajectory()
Get the optimal trajectory for a cycle for visualization.
Definition: optimizer.cpp:339
void shutdown()
Shutdown for optimizer at process end.
Definition: optimizer.cpp:57
void reset()
Reset the optimization problem to initial conditions.
Definition: optimizer.cpp:116
void setSpeedLimit(double speed_limit, bool percentage)
Set the maximum speed based on the speed limits callback.
Definition: optimizer.cpp:422
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:35
void setPath(const nav_msgs::msg::Path &plan)
Set new reference path.
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 add(const xt::xtensor< float, 2 > &trajectory, const std::string &marker_namespace)
Add an optimal trajectory to visualize.
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:68
void reset()
Reset the controller state between tasks.
Definition: controller.cpp:75
void cleanup() override
Cleanup resources.
Definition: controller.cpp:54
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:80
void setPlan(const nav_msgs::msg::Path &path) override
Set new reference path to track.
Definition: controller.cpp:123
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 visualize(nav_msgs::msg::Path transformed_plan)
Visualize trajectories.
Definition: controller.cpp:116
void setSpeedLimit(const double &speed_limit, const bool &percentage) override
Set new speed limit from callback.
Definition: controller.cpp:128
void activate() override
Activate controller.
Definition: controller.cpp:62
void deactivate() override
Deactivate controller.
Definition: controller.cpp:69