Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
optimizer.hpp
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 #ifndef NAV2_MPPI_CONTROLLER__OPTIMIZER_HPP_
16 #define NAV2_MPPI_CONTROLLER__OPTIMIZER_HPP_
17 
18 #include <Eigen/Dense>
19 
20 #include <string>
21 #include <memory>
22 #include <tuple>
23 
24 #include "rclcpp_lifecycle/lifecycle_node.hpp"
25 
26 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
27 #include "nav2_core/goal_checker.hpp"
28 #include "nav2_core/controller_exceptions.hpp"
29 #include "tf2_ros/buffer.hpp"
30 #include "pluginlib/class_loader.hpp"
31 
32 #include "geometry_msgs/msg/twist.hpp"
33 #include "geometry_msgs/msg/pose_stamped.hpp"
34 #include "geometry_msgs/msg/twist_stamped.hpp"
35 #include "nav_msgs/msg/path.hpp"
36 #include "nav2_util/geometry_utils.hpp"
37 
38 #include "nav2_mppi_controller/models/optimizer_settings.hpp"
39 #include "nav2_mppi_controller/motion_models.hpp"
40 #include "nav2_mppi_controller/critic_manager.hpp"
41 #include "nav2_mppi_controller/models/state.hpp"
42 #include "nav2_mppi_controller/models/trajectories.hpp"
43 #include "nav2_mppi_controller/models/path.hpp"
44 #include "nav2_mppi_controller/tools/noise_generator.hpp"
45 #include "nav2_mppi_controller/tools/parameters_handler.hpp"
46 #include "nav2_mppi_controller/tools/utils.hpp"
47 #include "nav2_mppi_controller/optimal_trajectory_validator.hpp"
48 
49 namespace mppi
50 {
51 
56 class Optimizer
57 {
58 public:
62  Optimizer() = default;
63 
68 
69 
78  void initialize(
79  nav2::LifecycleNode::WeakPtr parent, const std::string & name,
80  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros,
81  std::shared_ptr<tf2_ros::Buffer> tf_buffer,
82  ParametersHandler * dynamic_parameters_handler);
83 
87  void shutdown();
88 
98  std::tuple<geometry_msgs::msg::TwistStamped, Eigen::ArrayXXf> evalControl(
99  const geometry_msgs::msg::PoseStamped & robot_pose,
100  const geometry_msgs::msg::Twist & robot_speed, const nav_msgs::msg::Path & plan,
101  const geometry_msgs::msg::Pose & goal, nav2_core::GoalChecker * goal_checker);
102 
108 
113  Eigen::ArrayXXf getOptimizedTrajectory();
114 
120 
126  void setSpeedLimit(double speed_limit, bool percentage);
127 
132  void reset(bool reset_dynamic_speed_limits = true);
133 
139  {
140  return settings_;
141  }
142 
143 protected:
147  void optimize();
148 
156  void prepare(
157  const geometry_msgs::msg::PoseStamped & robot_pose,
158  const geometry_msgs::msg::Twist & robot_speed,
159  const nav_msgs::msg::Path & plan,
160  const geometry_msgs::msg::Pose & goal, nav2_core::GoalChecker * goal_checker);
161 
165  void getParams();
166 
171  void setMotionModel(const std::string & model);
172 
177  void shiftControlSequence();
178 
184 
189 
194  void updateStateVelocities(models::State & state) const;
195 
200  void updateInitialStateVelocities(models::State & state) const;
201 
208 
215  models::Trajectories & trajectories,
216  const models::State & state) const;
217 
224  Eigen::Array<float, Eigen::Dynamic, 3> & trajectories,
225  const Eigen::ArrayXXf & state) const;
226 
231  void updateControlSequence();
232 
238  geometry_msgs::msg::TwistStamped
239  getControlFromSequenceAsTwist(const builtin_interfaces::msg::Time & stamp);
240 
245  bool isHolonomic() const;
246 
251  void setOffset(double controller_frequency);
252 
257  bool fallback(bool fail);
258 
259 protected:
260  nav2::LifecycleNode::WeakPtr parent_;
261  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
262  nav2_costmap_2d::Costmap2D * costmap_;
263  std::string name_;
264  std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
265 
266  std::shared_ptr<MotionModel> motion_model_;
267 
268  ParametersHandler * parameters_handler_;
269  CriticManager critic_manager_;
270  NoiseGenerator noise_generator_;
271 
272  std::unique_ptr<pluginlib::ClassLoader<OptimalTrajectoryValidator>> validator_loader_;
273  OptimalTrajectoryValidator::Ptr trajectory_validator_;
274 
275  models::OptimizerSettings settings_;
276 
277  models::State state_;
278  models::ControlSequence control_sequence_;
279  std::array<mppi::models::Control, 4> control_history_;
280  models::Trajectories generated_trajectories_;
281  models::Path path_;
282  geometry_msgs::msg::Pose goal_;
283  Eigen::ArrayXf costs_;
284 
285  CriticData critics_data_ = {
286  state_, generated_trajectories_, path_, goal_,
287  costs_, settings_.model_dt, false, nullptr, nullptr,
288  std::nullopt, std::nullopt};
289 
290  rclcpp::Logger logger_{rclcpp::get_logger("MPPIController")};
291 };
292 
293 } // namespace mppi
294 
295 #endif // NAV2_MPPI_CONTROLLER__OPTIMIZER_HPP_
Manager of objective function plugins for scoring trajectories.
Generates noise trajectories from optimal trajectory.
Main algorithm optimizer of the MPPI Controller.
Definition: optimizer.hpp:57
void updateStateVelocities(models::State &state) const
Update velocities in state.
Definition: optimizer.cpp:343
const models::ControlSequence & getOptimalControlSequence()
Get the optimal control sequence for a cycle for visualization.
Definition: optimizer.cpp:476
void setMotionModel(const std::string &model)
Set the motion model of the vehicle platform.
Definition: optimizer.cpp:537
void setOffset(double controller_frequency)
Using control frequencies and time step size, determine if trajectory offset should be used to popula...
Definition: optimizer.cpp:131
Eigen::ArrayXXf getOptimizedTrajectory()
Get the optimal trajectory for a cycle for visualization.
Definition: optimizer.cpp:458
void reset(bool reset_dynamic_speed_limits=true)
Reset the optimization problem to initial conditions.
Definition: optimizer.cpp:152
rclcpp::Logger logger_
Caution, keep references.
Definition: optimizer.hpp:290
void prepare(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)
Prepare state information on new request for trajectory rollouts.
Definition: optimizer.cpp:251
std::tuple< geometry_msgs::msg::TwistStamped, Eigen::ArrayXXf > 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:182
void initialize(nav2::LifecycleNode::WeakPtr parent, const std::string &name, std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros, std::shared_ptr< tf2_ros::Buffer > tf_buffer, ParametersHandler *dynamic_parameters_handler)
Initializes optimizer on startup.
Definition: optimizer.cpp:33
void integrateStateVelocities(models::Trajectories &trajectories, const models::State &state) const
Rollout velocities in state to poses.
Definition: optimizer.cpp:417
const models::OptimizerSettings & getSettings() const
Get the motion model time step.
Definition: optimizer.hpp:138
~Optimizer()
Destructor for mppi::Optimizer.
Definition: optimizer.hpp:67
void updateControlSequence()
Update control sequence with state controls weighted by costs using softmax function.
Definition: optimizer.cpp:481
void generateNoisedTrajectories()
updates generated trajectories with noised trajectories from the last cycle's optimal control
Definition: optimizer.cpp:286
bool fallback(bool fail)
Perform fallback behavior to try to recover from a set of trajectories in collision.
Definition: optimizer.cpp:232
bool isHolonomic() const
Whether the motion model is holonomic.
Definition: optimizer.cpp:177
models::Trajectories & getGeneratedTrajectories()
Get the trajectories generated in a cycle for visualization.
Definition: optimizer.cpp:581
void updateInitialStateVelocities(models::State &state) const
Update initial velocity in state.
Definition: optimizer.cpp:350
void shutdown()
Shutdown for optimizer at process end.
Definition: optimizer.cpp:71
void optimize()
Main function to generate, score, and return trajectories.
Definition: optimizer.cpp:223
Optimizer()=default
Constructor for mppi::Optimizer.
void setSpeedLimit(double speed_limit, bool percentage)
Set the maximum speed based on the speed limits callback.
Definition: optimizer.cpp:554
void shiftControlSequence()
Shift the optimal control sequence after processing for next iterations initial conditions after exec...
Definition: optimizer.cpp:272
void applyControlSequenceConstraints()
Apply hard vehicle constraints on control sequence.
Definition: optimizer.cpp:294
void getParams()
Obtain the main controller's parameters.
Definition: optimizer.cpp:76
void propagateStateVelocitiesFromInitials(models::State &state) const
predict velocities in state using model for time horizon equal to timesteps
Definition: optimizer.cpp:361
geometry_msgs::msg::TwistStamped getControlFromSequenceAsTwist(const builtin_interfaces::msg::Time &stamp)
Convert control sequence to a twist command.
Definition: optimizer.cpp:521
Handles getting parameters and dynamic parameter changes.
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
Data to pass to critics for scoring, including state, trajectories, pruned path, global goal,...
Definition: critic_data.hpp:40
A control sequence over time (e.g. trajectory)
Settings for the optimizer to use.
Path represented as a tensor.
Definition: path.hpp:28
State information: velocities, controls, poses, speed.
Definition: state.hpp:32
Candidate Trajectories.