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 
37 #include "nav2_mppi_controller/models/optimizer_settings.hpp"
38 #include "nav2_mppi_controller/motion_models.hpp"
39 #include "nav2_mppi_controller/critic_manager.hpp"
40 #include "nav2_mppi_controller/models/state.hpp"
41 #include "nav2_mppi_controller/models/trajectories.hpp"
42 #include "nav2_mppi_controller/models/path.hpp"
43 #include "nav2_mppi_controller/tools/noise_generator.hpp"
44 #include "nav2_mppi_controller/tools/parameters_handler.hpp"
45 #include "nav2_mppi_controller/tools/utils.hpp"
46 #include "nav2_mppi_controller/optimal_trajectory_validator.hpp"
47 
48 namespace mppi
49 {
50 
55 class Optimizer
56 {
57 public:
61  Optimizer() = default;
62 
67 
68 
77  void initialize(
78  nav2::LifecycleNode::WeakPtr parent, const std::string & name,
79  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros,
80  std::shared_ptr<tf2_ros::Buffer> tf_buffer,
81  ParametersHandler * dynamic_parameters_handler);
82 
86  void shutdown();
87 
97  std::tuple<geometry_msgs::msg::TwistStamped, Eigen::ArrayXXf> evalControl(
98  const geometry_msgs::msg::PoseStamped & robot_pose,
99  const geometry_msgs::msg::Twist & robot_speed, const nav_msgs::msg::Path & plan,
100  const geometry_msgs::msg::Pose & goal, nav2_core::GoalChecker * goal_checker);
101 
107 
112  Eigen::ArrayXXf getOptimizedTrajectory();
113 
119 
125  void setSpeedLimit(double speed_limit, bool percentage);
126 
131  void reset(bool reset_dynamic_speed_limits = true);
132 
138  {
139  return settings_;
140  }
141 
142 protected:
146  void optimize();
147 
155  void prepare(
156  const geometry_msgs::msg::PoseStamped & robot_pose,
157  const geometry_msgs::msg::Twist & robot_speed,
158  const nav_msgs::msg::Path & plan,
159  const geometry_msgs::msg::Pose & goal, nav2_core::GoalChecker * goal_checker);
160 
164  void getParams();
165 
170  void setMotionModel(const std::string & model);
171 
176  void shiftControlSequence();
177 
183 
188 
193  void updateStateVelocities(models::State & state) const;
194 
199  void updateInitialStateVelocities(models::State & state) const;
200 
207 
214  models::Trajectories & trajectories,
215  const models::State & state) const;
216 
223  Eigen::Array<float, Eigen::Dynamic, 3> & trajectories,
224  const Eigen::ArrayXXf & state) const;
225 
230  void updateControlSequence();
231 
237  geometry_msgs::msg::TwistStamped
238  getControlFromSequenceAsTwist(const builtin_interfaces::msg::Time & stamp);
239 
244  bool isHolonomic() const;
245 
250  void setOffset(double controller_frequency);
251 
256  bool fallback(bool fail);
257 
258 protected:
259  nav2::LifecycleNode::WeakPtr parent_;
260  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
261  nav2_costmap_2d::Costmap2D * costmap_;
262  std::string name_;
263  std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
264 
265  std::shared_ptr<MotionModel> motion_model_;
266 
267  ParametersHandler * parameters_handler_;
268  CriticManager critic_manager_;
269  NoiseGenerator noise_generator_;
270 
271  std::unique_ptr<pluginlib::ClassLoader<OptimalTrajectoryValidator>> validator_loader_;
272  OptimalTrajectoryValidator::Ptr trajectory_validator_;
273 
274  models::OptimizerSettings settings_;
275 
276  models::State state_;
277  models::ControlSequence control_sequence_;
278  std::array<mppi::models::Control, 4> control_history_;
279  models::Trajectories generated_trajectories_;
280  models::Path path_;
281  geometry_msgs::msg::Pose goal_;
282  Eigen::ArrayXf costs_;
283 
284  CriticData critics_data_ = {
285  state_, generated_trajectories_, path_, goal_,
286  costs_, settings_.model_dt, false, nullptr, nullptr,
287  std::nullopt, std::nullopt};
288 
289  rclcpp::Logger logger_{rclcpp::get_logger("MPPIController")};
290 };
291 
292 } // namespace mppi
293 
294 #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:56
void updateStateVelocities(models::State &state) const
Update velocities in state.
Definition: optimizer.cpp:342
const models::ControlSequence & getOptimalControlSequence()
Get the optimal control sequence for a cycle for visualization.
Definition: optimizer.cpp:475
void setMotionModel(const std::string &model)
Set the motion model of the vehicle platform.
Definition: optimizer.cpp:536
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:457
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:289
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:416
const models::OptimizerSettings & getSettings() const
Get the motion model time step.
Definition: optimizer.hpp:137
~Optimizer()
Destructor for mppi::Optimizer.
Definition: optimizer.hpp:66
void updateControlSequence()
Update control sequence with state controls weighted by costs using softmax function.
Definition: optimizer.cpp:480
void generateNoisedTrajectories()
updates generated trajectories with noised trajectories from the last cycle's optimal control
Definition: optimizer.cpp:285
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:580
void updateInitialStateVelocities(models::State &state) const
Update initial velocity in state.
Definition: optimizer.cpp:349
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:553
void shiftControlSequence()
Shift the optimal control sequence after processing for next iterations initial conditions after exec...
Definition: optimizer.cpp:271
void applyControlSequenceConstraints()
Apply hard vehicle constraints on control sequence.
Definition: optimizer.cpp:293
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:360
geometry_msgs::msg::TwistStamped getControlFromSequenceAsTwist(const builtin_interfaces::msg::Time &stamp)
Convert control sequence to a twist command.
Definition: optimizer.cpp:520
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.