Nav2 Navigation Stack - jazzy
jazzy
ROS 2 Navigation Stack
|
Main algorithm optimizer of the MPPI Controller. More...
#include <nav2_mppi_controller/include/nav2_mppi_controller/optimizer.hpp>
Public Member Functions | |
Optimizer ()=default | |
Constructor for mppi::Optimizer. | |
~Optimizer () | |
Destructor for mppi::Optimizer. | |
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. More... | |
void | shutdown () |
Shutdown for optimizer at process end. | |
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. More... | |
models::Trajectories & | getGeneratedTrajectories () |
Get the trajectories generated in a cycle for visualization. More... | |
xt::xtensor< float, 2 > | getOptimizedTrajectory () |
Get the optimal trajectory for a cycle for visualization. More... | |
void | setSpeedLimit (double speed_limit, bool percentage) |
Set the maximum speed based on the speed limits callback. More... | |
void | reset (bool reset_dynamic_speed_limits=true) |
Reset the optimization problem to initial conditions. More... | |
Protected Member Functions | |
void | optimize () |
Main function to generate, score, and return trajectories. | |
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. More... | |
void | getParams () |
Obtain the main controller's parameters. | |
void | setMotionModel (const std::string &model) |
Set the motion model of the vehicle platform. More... | |
void | shiftControlSequence () |
Shift the optimal control sequence after processing for next iterations initial conditions after execution. | |
void | generateNoisedTrajectories () |
updates generated trajectories with noised trajectories from the last cycle's optimal control | |
void | applyControlSequenceConstraints () |
Apply hard vehicle constraints on control sequence. | |
void | updateStateVelocities (models::State &state) const |
Update velocities in state. More... | |
void | updateInitialStateVelocities (models::State &state) const |
Update initial velocity in state. More... | |
void | propagateStateVelocitiesFromInitials (models::State &state) const |
predict velocities in state using model for time horizon equal to timesteps More... | |
void | integrateStateVelocities (models::Trajectories &trajectories, const models::State &state) const |
Rollout velocities in state to poses. More... | |
void | integrateStateVelocities (xt::xtensor< float, 2 > &trajectories, const xt::xtensor< float, 2 > &state) const |
Rollout velocities in state to poses. More... | |
void | updateControlSequence () |
Update control sequence with state controls weighted by costs using softmax function. | |
geometry_msgs::msg::TwistStamped | getControlFromSequenceAsTwist (const builtin_interfaces::msg::Time &stamp) |
Convert control sequence to a twist commant. More... | |
bool | isHolonomic () const |
Whether the motion model is holonomic. More... | |
void | setOffset (double controller_frequency) |
Using control frequence and time step size, determine if trajectory offset should be used to populate initial state of the next cycle. | |
bool | fallback (bool fail) |
Perform fallback behavior to try to recover from a set of trajectories in collision. More... | |
Protected Attributes | |
rclcpp_lifecycle::LifecycleNode::WeakPtr | parent_ |
std::shared_ptr< nav2_costmap_2d::Costmap2DROS > | costmap_ros_ |
nav2_costmap_2d::Costmap2D * | costmap_ |
std::string | name_ |
std::shared_ptr< MotionModel > | motion_model_ |
ParametersHandler * | parameters_handler_ |
CriticManager | critic_manager_ |
NoiseGenerator | noise_generator_ |
models::OptimizerSettings | settings_ |
models::State | state_ |
models::ControlSequence | control_sequence_ |
std::array< mppi::models::Control, 4 > | control_history_ |
models::Trajectories | generated_trajectories_ |
models::Path | path_ |
geometry_msgs::msg::Pose | goal_ |
xt::xtensor< float, 1 > | costs_ |
CriticData | critics_data_ |
rclcpp::Logger | logger_ {rclcpp::get_logger("MPPIController")} |
Caution, keep references. | |
Main algorithm optimizer of the MPPI Controller.
Definition at line 57 of file optimizer.hpp.
geometry_msgs::msg::TwistStamped mppi::Optimizer::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.
robot_pose | Pose of the robot at given time |
robot_speed | Speed of the robot at given time |
plan | Path plan to track |
goal_checker | Object to check if goal is completed |
Definition at line 164 of file optimizer.cpp.
Referenced by nav2_mppi_controller::MPPIController::computeVelocityCommands().
|
protected |
Perform fallback behavior to try to recover from a set of trajectories in collision.
fail | Whether the system failed to recover from |
Definition at line 196 of file optimizer.cpp.
|
protected |
Convert control sequence to a twist commant.
stamp | Timestamp to use |
Definition at line 448 of file optimizer.cpp.
models::Trajectories & mppi::Optimizer::getGeneratedTrajectories | ( | ) |
Get the trajectories generated in a cycle for visualization.
Definition at line 508 of file optimizer.cpp.
Referenced by nav2_mppi_controller::MPPIController::visualize().
xt::xtensor< float, 2 > mppi::Optimizer::getOptimizedTrajectory | ( | ) |
Get the optimal trajectory for a cycle for visualization.
Definition at line 395 of file optimizer.cpp.
Referenced by nav2_mppi_controller::MPPIController::visualize().
void mppi::Optimizer::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.
parent | WeakPtr to node |
name | Name of plugin |
costmap_ros | Costmap2DROS object of environment |
dynamic_parameter_handler | Parameter handler object |
Definition at line 36 of file optimizer.cpp.
Referenced by nav2_mppi_controller::MPPIController::configure().
|
protected |
Rollout velocities in state to poses.
trajectories | to rollout |
state | fill state |
Definition at line 367 of file optimizer.cpp.
|
protected |
Rollout velocities in state to poses.
trajectories | to rollout |
state | fill state |
Definition at line 334 of file optimizer.cpp.
|
protected |
Whether the motion model is holonomic.
y
axis of state Definition at line 159 of file optimizer.cpp.
|
protected |
Prepare state information on new request for trajectory rollouts.
robot_pose | Pose of the robot at given time |
robot_speed | Speed of the robot at given time |
plan | Path plan to track |
goal_checker | Object to check if goal is completed |
Definition at line 215 of file optimizer.cpp.
|
protected |
predict velocities in state using model for time horizon equal to timesteps
state | fill state |
Definition at line 328 of file optimizer.cpp.
void mppi::Optimizer::reset | ( | bool | reset_dynamic_speed_limits = true | ) |
Reset the optimization problem to initial conditions.
Whether | to reset the constraints to its base values |
Definition at line 137 of file optimizer.cpp.
Referenced by nav2_mppi_controller::MPPIController::reset().
|
protected |
Set the motion model of the vehicle platform.
model | Model string to use |
Definition at line 464 of file optimizer.cpp.
void mppi::Optimizer::setSpeedLimit | ( | double | speed_limit, |
bool | percentage | ||
) |
Set the maximum speed based on the speed limits callback.
speed_limit | Limit of the speed for use |
percentage | Whether the speed limit is absolute or relative |
Definition at line 481 of file optimizer.cpp.
Referenced by nav2_mppi_controller::MPPIController::setSpeedLimit().
|
protected |
Update initial velocity in state.
state | fill state |
Definition at line 317 of file optimizer.cpp.
|
protected |
Update velocities in state.
state | fill state with velocities on each step |
Definition at line 310 of file optimizer.cpp.
|
protected |
Definition at line 264 of file optimizer.hpp.