mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-24 15:40:31 +08:00
docs: minor api updates for ros modes (#25563)
This commit is contained in:
@@ -262,9 +262,9 @@ This section steps through an example of how to create a mode executor class.
|
||||
class MyModeExecutor : public px4_ros2::ModeExecutorBase // [1]
|
||||
{
|
||||
public:
|
||||
MyModeExecutor(rclcpp::Node & node, px4_ros2::ModeBase & owned_mode) // [2]
|
||||
: ModeExecutorBase(node, px4_ros2::ModeExecutorBase::Settings{}, owned_mode),
|
||||
_node(node)
|
||||
MyModeExecutor(px4_ros2::ModeBase & owned_mode) // [2]
|
||||
: ModeExecutorBase(px4_ros2::ModeExecutorBase::Settings{}, owned_mode),
|
||||
_node(owned_mode.node())
|
||||
{ }
|
||||
|
||||
enum class State // [3]
|
||||
@@ -340,8 +340,8 @@ The used types also define the compatibility with different vehicle types.
|
||||
|
||||
The following sections provide a list of supported setpoint types:
|
||||
|
||||
- [GotoSetpointType](#go-to-setpoint-gotosetpointtype): Smooth position and (optionally) heading control
|
||||
- [FwLateralLongitudinalSetpointType](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype): <Badge type="tip" text="main (planned for: PX4 v1.17)" /> Direct control of lateral and longitudinal fixed wing dynamics
|
||||
- [MulticopterGotoSetpointType](#go-to-setpoint-multicoptergotosetpointtype): <Badge type="warning" text="MC only" /> Smooth position and (optionally) heading control
|
||||
- [FwLateralLongitudinalSetpointType](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype): <Badge type="warning" text="FW only" /> <Badge type="tip" text="main (planned for: PX4 v1.17)" /> Direct control of lateral and longitudinal fixed wing dynamics
|
||||
- [DirectActuatorsSetpointType](#direct-actuator-control-setpoint-directactuatorssetpointtype): Direct control of motors and flight surface servo setpoints
|
||||
|
||||
:::tip
|
||||
@@ -350,15 +350,19 @@ The other setpoint types are currently experimental, and can be found in: [px4_r
|
||||
You can add your own setpoint types by adding a class that inherits from `px4_ros2::SetpointBase`, sets the configuration flags according to what the setpoint requires, and then publishes any topic containing a setpoint.
|
||||
:::
|
||||
|
||||
#### Go-to Setpoint (GotoSetpointType)
|
||||
#### Go-to Setpoint (MulticopterGotoSetpointType)
|
||||
|
||||
<Badge type="warning" text="MC only" />
|
||||
|
||||
::: info
|
||||
This setpoint type is currently only supported for multicopters.
|
||||
:::
|
||||
|
||||
Smoothly control position and (optionally) heading setpoints with the [`px4_ros2::GotoSetpointType`](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/goto.hpp) setpoint type.
|
||||
Smoothly control position and (optionally) heading setpoints with the [`px4_ros2::MulticopterGotoSetpointType`](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/multicopter/goto.hpp) setpoint type.
|
||||
The setpoint type is streamed to FMU based position and heading smoothers formulated with time-optimal, maximum-jerk trajectories, with velocity and acceleration constraints.
|
||||
|
||||
There is also a [`px4_ros2::MulticopterGotoGlobalSetpointType`](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/multicopter/goto.hpp) class that allows to send setpoints in global coordinates.
|
||||
|
||||
The most trivial use is simply inputting a 3D position into the update method:
|
||||
|
||||
```cpp
|
||||
@@ -549,7 +553,7 @@ If you want to control an actuator that does not control the vehicle's motion, b
|
||||
|
||||
To control a VTOL in an external flight mode, ensure you're returning the correct setpoint type based on the current flight configuration:
|
||||
|
||||
- Multicopter mode: use a setpoint type that is compatible with multicopter control. For example: either the [`GotoSetpointType`](#go-to-setpoint-gotosetpointtype) or the [`TrajectorySetpointType`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1TrajectorySetpointType.html).
|
||||
- Multicopter mode: use a setpoint type that is compatible with multicopter control. For example: either the [`MulticopterGotoSetpointType`](#go-to-setpoint-multicoptergotosetpointtype) or the [`TrajectorySetpointType`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1TrajectorySetpointType.html).
|
||||
- Fixed-wing mode: Use the [`FwLateralLongitudinalSetpointType`](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype).
|
||||
|
||||
As long as the VTOL remains in either multicopter or fixed-wing mode throughout the external mode, no additional handling is required.
|
||||
|
||||
Reference in New Issue
Block a user