diff --git a/configuration/packages/configuring-mppic.rst b/configuration/packages/configuring-mppic.rst index 341f3d728..e4a0e69cc 100644 --- a/configuration/packages/configuring-mppic.rst +++ b/configuration/packages/configuring-mppic.rst @@ -35,11 +35,23 @@ MPPI Parameters ============== =========================== Type Default -------------- --------------------------- - string "DiffDrive" + string "diff_drive" ============== =========================== Description - The desired motion model to use for trajectory planning. Options are ``DiffDrive``, ``Omni``, or ``Ackermann``. Differential drive robots may use forward/reverse and angular velocities; Omni add in lateral motion; and Ackermann adds minimum curvature constraints. + The desired motion model plugin to use for trajectory planning. The plugin type is required to be specified in the corresponding namespace. + +:````.plugin: + + ============== =========================== + Type Default + -------------- --------------------------- + string N/A + ============== =========================== + + Description + The plugin to use for the motion model constraints of the MPPI planner. + Supported motion model plugins include "mppi::DiffDriveMotionModel", "mppi::OmniMotionModel", and "mppi::AckermannMotionModel" for differential drive, omnidirectional, and Ackermann robots respectively. :critics: @@ -374,10 +386,10 @@ Trajectory Visualization Description Whether to allow QoS profiles to be overwritten with parameterized values. -Ackermann Motion Model ----------------------- +AckermannMotionModel +-------------------- -:min_turning_r: +:````.min_turning_r: ============== =========================== Type Default @@ -386,7 +398,7 @@ Ackermann Motion Model ============== =========================== Description - The minimum turning radius possible for the vehicle platform (m). + The minimum turning radius possible for the vehicle platform (m). This is only used if ````.plugin is set to "mppi::AckermannMotionModel". Default Optimal Trajectory Validator ------------------------------------ @@ -1085,7 +1097,9 @@ Example iteration_count: 1 temperature: 0.3 gamma: 0.015 - motion_model: "DiffDrive" + motion_model: "diff_drive" + diff_drive: + plugin: "mppi::DiffDriveMotionModel" visualize: false critic_index_to_visualize: 0 reset_period: 1.0 # (only in Humble) @@ -1097,8 +1111,6 @@ Example plugin: "mppi::DefaultOptimalTrajectoryValidator" collision_lookahead_time: 2.0 consider_footprint: false - AckermannConstraints: - min_turning_r: 0.2 critics: ["ConstraintCritic", "CostCritic", "GoalCritic", "GoalAngleCritic", "PathAlignCritic", "PathFollowCritic", "PathAngleCritic", "PreferForwardCritic"] ConstraintCritic: enabled: true diff --git a/migration/Kilted.rst b/migration/Kilted.rst index 165c727e4..360be2192 100644 --- a/migration/Kilted.rst +++ b/migration/Kilted.rst @@ -945,3 +945,25 @@ Global planner plugin natively accepts viapoints `PR #5995 `_ updates the ``createPath`` API for the ``BaseGlobalPlanner`` to include a vector ``std::vector`` argument that takes in a list of intermediate points and passes them to the planner plugin implementation. The function signature for ``createPath`` must be updated accordingly for all custom planner plugins inheriting from the ``BaseGlobalPlanner``. This change does not alter the behavior of ``ComputePathThroughPoses`` that connects consecutive segments end-to-end but does upgrade the ``ComputePathToPose`` action. + +MPPI motion models use plugin-based configuration +-------------------------------------------------- + +`PR #6076 `_ adds support for plugin-based configuration of motion models in MPPI. + +Motion model now has to be set up by specifying plugin to use: + +.. code-block:: yaml + + MPPIController: + plugin: "nav2_mppi_controller::MPPIController" + motion_model: "diff_drive" + diff_drive: + plugin: "mppi::DiffDriveMotionModel" + +Supported motion model plugins are: + - ``mppi::DiffDriveMotionModel`` : replaces ``motion_model: DiffDrive`` + - ``mppi::OmniMotionModel`` : replaces ``motion_model: Omni`` + - ``mppi::AckermannMotionModel`` : replaces ``motion_model: Ackermann`` + +While "diff_drive" is the default value for ``motion_model`` parameter, it is still required to specify the plugin for it, as shown above.