Nav2 Navigation Stack - kilted  kilted
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 
23 #include "rclcpp_lifecycle/lifecycle_node.hpp"
24 
25 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
26 #include "nav2_core/goal_checker.hpp"
27 #include "nav2_core/controller_exceptions.hpp"
28 
29 #include "geometry_msgs/msg/twist.hpp"
30 #include "geometry_msgs/msg/pose_stamped.hpp"
31 #include "geometry_msgs/msg/twist_stamped.hpp"
32 #include "nav_msgs/msg/path.hpp"
33 
34 #include "nav2_mppi_controller/models/optimizer_settings.hpp"
35 #include "nav2_mppi_controller/motion_models.hpp"
36 #include "nav2_mppi_controller/critic_manager.hpp"
37 #include "nav2_mppi_controller/models/state.hpp"
38 #include "nav2_mppi_controller/models/trajectories.hpp"
39 #include "nav2_mppi_controller/models/path.hpp"
40 #include "nav2_mppi_controller/tools/noise_generator.hpp"
41 #include "nav2_mppi_controller/tools/parameters_handler.hpp"
42 #include "nav2_mppi_controller/tools/utils.hpp"
43 
44 namespace mppi
45 {
46 
51 class Optimizer
52 {
53 public:
57  Optimizer() = default;
58 
63 
64 
72  void initialize(
73  rclcpp_lifecycle::LifecycleNode::WeakPtr parent, const std::string & name,
74  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros,
75  ParametersHandler * dynamic_parameters_handler);
76 
80  void shutdown();
81 
91  geometry_msgs::msg::TwistStamped evalControl(
92  const geometry_msgs::msg::PoseStamped & robot_pose,
93  const geometry_msgs::msg::Twist & robot_speed, const nav_msgs::msg::Path & plan,
94  const geometry_msgs::msg::Pose & goal, nav2_core::GoalChecker * goal_checker);
95 
101 
106  Eigen::ArrayXXf getOptimizedTrajectory();
107 
113 
119  void setSpeedLimit(double speed_limit, bool percentage);
120 
125  void reset(bool reset_dynamic_speed_limits = true);
126 
132  {
133  return settings_;
134  }
135 
136 protected:
140  void optimize();
141 
149  void prepare(
150  const geometry_msgs::msg::PoseStamped & robot_pose,
151  const geometry_msgs::msg::Twist & robot_speed,
152  const nav_msgs::msg::Path & plan,
153  const geometry_msgs::msg::Pose & goal, nav2_core::GoalChecker * goal_checker);
154 
158  void getParams();
159 
164  void setMotionModel(const std::string & model);
165 
170  void shiftControlSequence();
171 
177 
182 
187  void updateStateVelocities(models::State & state) const;
188 
193  void updateInitialStateVelocities(models::State & state) const;
194 
201 
208  models::Trajectories & trajectories,
209  const models::State & state) const;
210 
217  Eigen::Array<float, Eigen::Dynamic, 3> & trajectories,
218  const Eigen::ArrayXXf & state) const;
219 
224  void updateControlSequence();
225 
231  geometry_msgs::msg::TwistStamped
232  getControlFromSequenceAsTwist(const builtin_interfaces::msg::Time & stamp);
233 
238  bool isHolonomic() const;
239 
244  void setOffset(double controller_frequency);
245 
250  bool fallback(bool fail);
251 
252 protected:
253  rclcpp_lifecycle::LifecycleNode::WeakPtr parent_;
254  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
255  nav2_costmap_2d::Costmap2D * costmap_;
256  std::string name_;
257 
258  std::shared_ptr<MotionModel> motion_model_;
259 
260  ParametersHandler * parameters_handler_;
261  CriticManager critic_manager_;
262  NoiseGenerator noise_generator_;
263 
264  models::OptimizerSettings settings_;
265 
266  models::State state_;
267  models::ControlSequence control_sequence_;
268  std::array<mppi::models::Control, 4> control_history_;
269  models::Trajectories generated_trajectories_;
270  models::Path path_;
271  geometry_msgs::msg::Pose goal_;
272  Eigen::ArrayXf costs_;
273 
274  CriticData critics_data_ = {
275  state_, generated_trajectories_, path_, goal_,
276  costs_, settings_.model_dt, false, nullptr, nullptr,
277  std::nullopt, std::nullopt};
278 
279  rclcpp::Logger logger_{rclcpp::get_logger("MPPIController")};
280 };
281 
282 } // namespace mppi
283 
284 #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:52
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
void updateStateVelocities(models::State &state) const
Update velocities in state.
Definition: optimizer.cpp:304
const models::ControlSequence & getOptimalControlSequence()
Get the optimal control sequence for a cycle for visualization.
Definition: optimizer.cpp:434
void setMotionModel(const std::string &model)
Set the motion model of the vehicle platform.
Definition: optimizer.cpp:495
void setOffset(double controller_frequency)
Using control frequencies and time step size, determine if trajectory offset should be used to popula...
Definition: optimizer.cpp:114
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
rclcpp::Logger logger_
Caution, keep references.
Definition: optimizer.hpp:279
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:213
void integrateStateVelocities(models::Trajectories &trajectories, const models::State &state) const
Rollout velocities in state to poses.
Definition: optimizer.cpp:375
const models::OptimizerSettings & getSettings() const
Get the motion model time step.
Definition: optimizer.hpp:131
~Optimizer()
Destructor for mppi::Optimizer.
Definition: optimizer.hpp:62
void updateControlSequence()
Update control sequence with state controls weighted by costs using softmax function.
Definition: optimizer.cpp:439
void generateNoisedTrajectories()
updates generated trajectories with noised trajectories from the last cycle's optimal control
Definition: optimizer.cpp:247
bool fallback(bool fail)
Perform fallback behavior to try to recover from a set of trajectories in collision.
Definition: optimizer.cpp:194
bool isHolonomic() const
Whether the motion model is holonomic.
Definition: optimizer.cpp:157
models::Trajectories & getGeneratedTrajectories()
Get the trajectories generated in a cycle for visualization.
Definition: optimizer.cpp:539
void updateInitialStateVelocities(models::State &state) const
Update initial velocity in state.
Definition: optimizer.cpp:311
void shutdown()
Shutdown for optimizer at process end.
Definition: optimizer.cpp:54
void optimize()
Main function to generate, score, and return trajectories.
Definition: optimizer.cpp:185
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:512
void shiftControlSequence()
Shift the optimal control sequence after processing for next iterations initial conditions after exec...
Definition: optimizer.cpp:233
void applyControlSequenceConstraints()
Apply hard vehicle constraints on control sequence.
Definition: optimizer.cpp:255
void getParams()
Obtain the main controller's parameters.
Definition: optimizer.cpp:59
void propagateStateVelocitiesFromInitials(models::State &state) const
predict velocities in state using model for time horizon equal to timesteps
Definition: optimizer.cpp:322
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
geometry_msgs::msg::TwistStamped getControlFromSequenceAsTwist(const builtin_interfaces::msg::Time &stamp)
Convert control sequence to a twist command.
Definition: optimizer.cpp:479
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.