Nav2 Navigation Stack - humble  humble
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 #include <xtensor/xtensor.hpp>
22 #include <xtensor/xview.hpp>
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 
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 
90  geometry_msgs::msg::TwistStamped evalControl(
91  const geometry_msgs::msg::PoseStamped & robot_pose,
92  const geometry_msgs::msg::Twist & robot_speed, const nav_msgs::msg::Path & plan,
93  const geometry_msgs::msg::Pose & goal, nav2_core::GoalChecker * goal_checker);
94 
100 
105  xt::xtensor<float, 2> getOptimizedTrajectory();
106 
112  void setSpeedLimit(double speed_limit, bool percentage);
113 
117  void reset();
118 
119 protected:
123  void optimize();
124 
132  void prepare(
133  const geometry_msgs::msg::PoseStamped & robot_pose,
134  const geometry_msgs::msg::Twist & robot_speed,
135  const nav_msgs::msg::Path & plan,
136  const geometry_msgs::msg::Pose & goal, nav2_core::GoalChecker * goal_checker);
137 
141  void getParams();
142 
147  void setMotionModel(const std::string & model);
148 
153  void shiftControlSequence();
154 
160 
165 
170  void updateStateVelocities(models::State & state) const;
171 
176  void updateInitialStateVelocities(models::State & state) const;
177 
184 
191  models::Trajectories & trajectories,
192  const models::State & state) const;
193 
200  xt::xtensor<float, 2> & trajectories,
201  const xt::xtensor<float, 2> & state) const;
202 
207  void updateControlSequence();
208 
214  geometry_msgs::msg::TwistStamped
215  getControlFromSequenceAsTwist(const builtin_interfaces::msg::Time & stamp);
216 
221  bool isHolonomic() const;
222 
227  void setOffset(double controller_frequency);
228 
233  bool fallback(bool fail);
234 
235 protected:
236  rclcpp_lifecycle::LifecycleNode::WeakPtr parent_;
237  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
238  nav2_costmap_2d::Costmap2D * costmap_;
239  std::string name_;
240 
241  std::shared_ptr<MotionModel> motion_model_;
242 
243  ParametersHandler * parameters_handler_;
244  CriticManager critic_manager_;
245  NoiseGenerator noise_generator_;
246 
247  models::OptimizerSettings settings_;
248 
249  models::State state_;
250  models::ControlSequence control_sequence_;
251  std::array<mppi::models::Control, 4> control_history_;
252  models::Trajectories generated_trajectories_;
253  models::Path path_;
254  geometry_msgs::msg::Pose goal_;
255  xt::xtensor<float, 1> costs_;
256 
257  CriticData critics_data_ = {
258  state_, generated_trajectories_, path_, goal_,
259  costs_, settings_.model_dt, false, nullptr, nullptr,
260  std::nullopt, std::nullopt};
261 
262  rclcpp::Logger logger_{rclcpp::get_logger("MPPIController")};
263 };
264 
265 } // namespace mppi
266 
267 #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:134
void updateStateVelocities(models::State &state) const
Update velocities in state.
Definition: optimizer.cpp:251
void setMotionModel(const std::string &model)
Set the motion model of the vehicle platform.
Definition: optimizer.cpp:412
void setOffset(double controller_frequency)
Using control frequence and time step size, determine if trajectory offset should be used to populate...
Definition: optimizer.cpp:95
rclcpp::Logger logger_
Caution, keep references.
Definition: optimizer.hpp:262
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:185
void integrateStateVelocities(models::Trajectories &trajectories, const models::State &state) const
Rollout velocities in state to poses.
Definition: optimizer.cpp:313
~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:362
void generateNoisedTrajectories()
updates generated trajectories with noised trajectories from the last cycle's optimal control
Definition: optimizer.cpp:227
bool fallback(bool fail)
Perform fallback behavior to try to recover from a set of trajectories in collision.
Definition: optimizer.cpp:166
bool isHolonomic() const
Whether the motion model is holonomic.
Definition: optimizer.cpp:235
models::Trajectories & getGeneratedTrajectories()
Get the trajectories generated in a cycle for visualization.
Definition: optimizer.cpp:455
void updateInitialStateVelocities(models::State &state) const
Update initial velocity in state.
Definition: optimizer.cpp:258
xt::xtensor< float, 2 > getOptimizedTrajectory()
Get the optimal trajectory for a cycle for visualization.
Definition: optimizer.cpp:345
void shutdown()
Shutdown for optimizer at process end.
Definition: optimizer.cpp:57
void optimize()
Main function to generate, score, and return trajectories.
Definition: optimizer.cpp:157
void reset()
Reset the optimization problem to initial conditions.
Definition: optimizer.cpp:116
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:428
void shiftControlSequence()
Shift the optimal control sequence after processing for next iterations initial conditions after exec...
Definition: optimizer.cpp:206
void applyControlSequenceConstraints()
Apply hard vehicle constraints on control sequence.
Definition: optimizer.cpp:237
void getParams()
Obtain the main controller's parameters.
Definition: optimizer.cpp:62
void propagateStateVelocitiesFromInitials(models::State &state) const
predict velocities in state using model for time horizon equal to timesteps
Definition: optimizer.cpp:269
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
geometry_msgs::msg::TwistStamped getControlFromSequenceAsTwist(const builtin_interfaces::msg::Time &stamp)
Convert control sequence to a twist commant.
Definition: optimizer.cpp:396
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:39
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:31
Candidate Trajectories.