Nav2 Navigation Stack - jazzy  jazzy
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 <string>
19 #include <memory>
20 
21 // xtensor creates warnings that needs to be ignored as we are building with -Werror
22 #pragma GCC diagnostic push
23 #pragma GCC diagnostic ignored "-Warray-bounds"
24 #pragma GCC diagnostic ignored "-Wstringop-overflow"
25 #include <xtensor/xtensor.hpp>
26 #include <xtensor/xview.hpp>
27 #pragma GCC diagnostic pop
28 
29 #include "rclcpp_lifecycle/lifecycle_node.hpp"
30 
31 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
32 #include "nav2_core/goal_checker.hpp"
33 #include "nav2_core/controller_exceptions.hpp"
34 
35 #include "geometry_msgs/msg/twist.hpp"
36 #include "geometry_msgs/msg/pose_stamped.hpp"
37 #include "geometry_msgs/msg/twist_stamped.hpp"
38 #include "nav_msgs/msg/path.hpp"
39 
40 #include "nav2_mppi_controller/models/optimizer_settings.hpp"
41 #include "nav2_mppi_controller/motion_models.hpp"
42 #include "nav2_mppi_controller/critic_manager.hpp"
43 #include "nav2_mppi_controller/models/state.hpp"
44 #include "nav2_mppi_controller/models/trajectories.hpp"
45 #include "nav2_mppi_controller/models/path.hpp"
46 #include "nav2_mppi_controller/tools/noise_generator.hpp"
47 #include "nav2_mppi_controller/tools/parameters_handler.hpp"
48 #include "nav2_mppi_controller/tools/utils.hpp"
49 
50 namespace mppi
51 {
52 
57 class Optimizer
58 {
59 public:
63  Optimizer() = default;
64 
69 
70 
78  void initialize(
79  rclcpp_lifecycle::LifecycleNode::WeakPtr parent, const std::string & name,
80  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros,
81  ParametersHandler * dynamic_parameters_handler);
82 
86  void shutdown();
87 
96  geometry_msgs::msg::TwistStamped evalControl(
97  const geometry_msgs::msg::PoseStamped & robot_pose,
98  const geometry_msgs::msg::Twist & robot_speed, const nav_msgs::msg::Path & plan,
99  const geometry_msgs::msg::Pose & goal, nav2_core::GoalChecker * goal_checker);
100 
106 
111  xt::xtensor<float, 2> getOptimizedTrajectory();
112 
118  void setSpeedLimit(double speed_limit, bool percentage);
119 
124  void reset(bool reset_dynamic_speed_limits = true);
125 
126 protected:
130  void optimize();
131 
139  void prepare(
140  const geometry_msgs::msg::PoseStamped & robot_pose,
141  const geometry_msgs::msg::Twist & robot_speed,
142  const nav_msgs::msg::Path & plan,
143  const geometry_msgs::msg::Pose & goal, nav2_core::GoalChecker * goal_checker);
144 
148  void getParams();
149 
154  void setMotionModel(const std::string & model);
155 
160  void shiftControlSequence();
161 
167 
172 
177  void updateStateVelocities(models::State & state) const;
178 
183  void updateInitialStateVelocities(models::State & state) const;
184 
191 
198  models::Trajectories & trajectories,
199  const models::State & state) const;
200 
207  xt::xtensor<float, 2> & trajectories,
208  const xt::xtensor<float, 2> & state) const;
209 
214  void updateControlSequence();
215 
221  geometry_msgs::msg::TwistStamped
222  getControlFromSequenceAsTwist(const builtin_interfaces::msg::Time & stamp);
223 
228  bool isHolonomic() const;
229 
234  void setOffset(double controller_frequency);
235 
240  bool fallback(bool fail);
241 
242 protected:
243  rclcpp_lifecycle::LifecycleNode::WeakPtr parent_;
244  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
245  nav2_costmap_2d::Costmap2D * costmap_;
246  std::string name_;
247 
248  std::shared_ptr<MotionModel> motion_model_;
249 
250  ParametersHandler * parameters_handler_;
251  CriticManager critic_manager_;
252  NoiseGenerator noise_generator_;
253 
254  models::OptimizerSettings settings_;
255 
256  models::State state_;
257  models::ControlSequence control_sequence_;
258  std::array<mppi::models::Control, 4> control_history_;
259  models::Trajectories generated_trajectories_;
260  models::Path path_;
261  geometry_msgs::msg::Pose goal_;
262  xt::xtensor<float, 1> costs_;
263 
264  CriticData critics_data_ = {
265  state_, generated_trajectories_, path_, goal_,
266  costs_, settings_.model_dt, false, nullptr, nullptr,
267  std::nullopt, std::nullopt};
268 
269  rclcpp::Logger logger_{rclcpp::get_logger("MPPIController")};
270 };
271 
272 } // namespace mppi
273 
274 #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:58
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:164
void updateStateVelocities(models::State &state) const
Update velocities in state.
Definition: optimizer.cpp:310
void setMotionModel(const std::string &model)
Set the motion model of the vehicle platform.
Definition: optimizer.cpp:464
void setOffset(double controller_frequency)
Using control frequence and time step size, determine if trajectory offset should be used to populate...
Definition: optimizer.cpp:116
void reset(bool reset_dynamic_speed_limits=true)
Reset the optimization problem to initial conditions.
Definition: optimizer.cpp:137
rclcpp::Logger logger_
Caution, keep references.
Definition: optimizer.hpp:269
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:215
void integrateStateVelocities(models::Trajectories &trajectories, const models::State &state) const
Rollout velocities in state to poses.
Definition: optimizer.cpp:367
~Optimizer()
Destructor for mppi::Optimizer.
Definition: optimizer.hpp:68
void updateControlSequence()
Update control sequence with state controls weighted by costs using softmax function.
Definition: optimizer.cpp:413
void generateNoisedTrajectories()
updates generated trajectories with noised trajectories from the last cycle's optimal control
Definition: optimizer.cpp:256
bool fallback(bool fail)
Perform fallback behavior to try to recover from a set of trajectories in collision.
Definition: optimizer.cpp:196
bool isHolonomic() const
Whether the motion model is holonomic.
Definition: optimizer.cpp:159
models::Trajectories & getGeneratedTrajectories()
Get the trajectories generated in a cycle for visualization.
Definition: optimizer.cpp:508
void updateInitialStateVelocities(models::State &state) const
Update initial velocity in state.
Definition: optimizer.cpp:317
xt::xtensor< float, 2 > getOptimizedTrajectory()
Get the optimal trajectory for a cycle for visualization.
Definition: optimizer.cpp:395
void shutdown()
Shutdown for optimizer at process end.
Definition: optimizer.cpp:58
void optimize()
Main function to generate, score, and return trajectories.
Definition: optimizer.cpp:187
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:481
void shiftControlSequence()
Shift the optimal control sequence after processing for next iterations initial conditions after exec...
Definition: optimizer.cpp:235
void applyControlSequenceConstraints()
Apply hard vehicle constraints on control sequence.
Definition: optimizer.cpp:264
void getParams()
Obtain the main controller's parameters.
Definition: optimizer.cpp:63
void propagateStateVelocitiesFromInitials(models::State &state) const
predict velocities in state using model for time horizon equal to timesteps
Definition: optimizer.cpp:328
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:36
geometry_msgs::msg::TwistStamped getControlFromSequenceAsTwist(const builtin_interfaces::msg::Time &stamp)
Convert control sequence to a twist commant.
Definition: optimizer.cpp:448
Handles getting parameters and dynamic parmaeter 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:68
Data to pass to critics for scoring, including state, trajectories, pruned path, global goal,...
Definition: critic_data.hpp:45
A control sequence over time (e.g. trajectory)
Settings for the optimizer to use.
Path represented as a tensor.
Definition: path.hpp:33
State information: velocities, controls, poses, speed.
Definition: state.hpp:36
Candidate Trajectories.