diff --git a/ja/flight_modes/offboard.md b/ja/flight_modes/offboard.md index f5a230d416da..c91ea0b3cff4 100644 --- a/ja/flight_modes/offboard.md +++ b/ja/flight_modes/offboard.md @@ -2,9 +2,11 @@ -The vehicle obeys position, velocity, acceleration, attitude, attitude rates or thrust/torque setpoints provided by some source that is external to the flight stack, such as a companion computer. The setpoints may be provided using MAVLink (or a MAVLink API such as [MAVSDK](https://mavsdk.mavlink.io/)) or by [ROS 2](../ros2/index.md). +The vehicle obeys position, velocity, acceleration, attitude, attitude rates or thrust/torque setpoints provided by some source that is external to the flight stack, such as a companion computer. +The setpoints may be provided using MAVLink (or a MAVLink API such as [MAVSDK](https://mavsdk.mavlink.io/)) or by [ROS 2](../ros2/index.md). -PX4 requires that the external controller provides a continuous 2Hz "proof of life" signal, by streaming any of the supported MAVLink setpoint messages or the ROS 2 [OffboardControlMode](../msg_docs/OffboardControlMode.md) message. PX4 enables offboard control only after receiving the signal for more than a second, and will regain control if the signal stops. +PX4 requires that the external controller provides a continuous 2Hz "proof of life" signal, by streaming any of the supported MAVLink setpoint messages or the ROS 2 [OffboardControlMode](../msg_docs/OffboardControlMode.md) message. +PX4 enables offboard control only after receiving the signal for more than a second, and will regain control if the signal stops. ::: info @@ -12,7 +14,8 @@ PX4 requires that the external controller provides a continuous 2Hz "proof of li - RC control is disabled except to change modes (you can also fly without any manual controller at all by setting the parameter [COM_RC_IN_MODE](../advanced_config/parameter_reference.md#COM_RC_IN_MODE) to 4: Stick input disabled). - The vehicle must be already be receiving a stream of MAVLink setpoint messages or ROS 2 [OffboardControlMode](../msg_docs/OffboardControlMode.md) messages before arming in offboard mode or switching to offboard mode when flying. - The vehicle will exit offboard mode if MAVLink setpoint messages or `OffboardControlMode` are not received at a rate of > 2Hz. -- Not all coordinate frames and field values allowed by MAVLink are supported for all setpoint messages and vehicles. Read the sections below _carefully_ to ensure only supported values are used. +- Not all coordinate frames and field values allowed by MAVLink are supported for all setpoint messages and vehicles. + Read the sections below _carefully_ to ensure only supported values are used. ::: @@ -20,27 +23,35 @@ PX4 requires that the external controller provides a continuous 2Hz "proof of li Offboard mode is used for controlling vehicle movement and attitude, by setting position, velocity, acceleration, attitude, attitude rates or thrust/torque setpoints. -PX4 must receive a stream of MAVLink setpoint messages or the ROS 2 [OffboardControlMode](../msg_docs/OffboardControlMode.md) at 2 Hz as proof that the external controller is healthy. The stream must be sent for at least a second before PX4 will arm in offboard mode, or switch to offboard mode when flying. If the rate falls below 2Hz while under external control PX4 will switch out of offboard mode after a timeout ([COM_OF_LOSS_T](#COM_OF_LOSS_T)), and attempt to land or perform some other failsafe action. The action depends on whether or not RC control is available, and is defined in the parameter [COM_OBL_RC_ACT](#COM_OBL_RC_ACT). +PX4 must receive a stream of MAVLink setpoint messages or the ROS 2 [OffboardControlMode](../msg_docs/OffboardControlMode.md) at 2 Hz as proof that the external controller is healthy. +The stream must be sent for at least a second before PX4 will arm in offboard mode, or switch to offboard mode when flying. +If the rate falls below 2Hz while under external control PX4 will switch out of offboard mode after a timeout ([COM_OF_LOSS_T](#COM_OF_LOSS_T)), and attempt to land or perform some other failsafe action. +The action depends on whether or not RC control is available, and is defined in the parameter [COM_OBL_RC_ACT](#COM_OBL_RC_ACT). -When using MAVLink the setpoint messages convey both the signal to indicate that the external source is "alive", and the setpoint value itself. In order to hold position in this case the vehicle must receive a stream of setpoints for the current position. +When using MAVLink the setpoint messages convey both the signal to indicate that the external source is "alive", and the setpoint value itself. +In order to hold position in this case the vehicle must receive a stream of setpoints for the current position. -When using ROS 2 the proof that the external source is alive is provided by a stream of [OffboardControlMode](../msg_docs/OffboardControlMode.md) messages, while the actual setpoint is provided by publishing to one of the setpoint uORB topics, such as [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md). In order to hold position in this case the vehicle must receive a stream of `OffboardControlMode` but would only need the `TrajectorySetpoint` once. +When using ROS 2 the proof that the external source is alive is provided by a stream of [OffboardControlMode](../msg_docs/OffboardControlMode.md) messages, while the actual setpoint is provided by publishing to one of the setpoint uORB topics, such as [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md). +In order to hold position in this case the vehicle must receive a stream of `OffboardControlMode` but would only need the `TrajectorySetpoint` once. -Note that offboard mode only supports a very limited set of MAVLink commands and messages. Operations, like taking off, landing, return to launch, may be best handled using the appropriate modes. Operations like uploading, downloading missions can be performed in any mode. +Note that offboard mode only supports a very limited set of MAVLink commands and messages. +Operations, like taking off, landing, return to launch, may be best handled using the appropriate modes. +Operations like uploading, downloading missions can be performed in any mode. ## ROS 2 Messages -The following ROS 2 messages and their particular fields and field values are allowed for the specified frames. In addition to providing heartbeat functionality, `OffboardControlMode` has two other main purposes: +The following ROS 2 messages and their particular fields and field values are allowed for the specified frames. +In addition to providing heartbeat functionality, `OffboardControlMode` has two other main purposes: 1. Controls the level of the [PX4 control architecture](../flight_stack/controller_diagrams.md) at which offboard setpoints must be injected, and disables the bypassed controllers. -1. Determines which valid estimates (position or velocity) are required, and also which setpoint messages should be used. +2. Determines which valid estimates (position or velocity) are required, and also which setpoint messages should be used. The `OffboardControlMode` message is defined as shown. ```sh # Off-board control mode -uint64 timestamp # time since system start (microseconds) +uint64 timestamp # time since system start (microseconds) bool position bool velocity @@ -51,21 +62,24 @@ bool thrust_and_torque bool direct_actuator ``` -The fields are ordered in terms of priority such that `position` takes precedence over `velocity` and later fields, `velocity` takes precedence over `acceleration`, and so on. The first field that has a non-zero value (from top to bottom) defines what valid estimate is required in order to use offboard mode, and the setpoint message(s) that can be used. For example, if the `acceleration` field is the first non-zero value, then PX4 requires a valid `velocity estimate`, and the setpoint must be specified using the `TrajectorySetpoint` message. +The fields are ordered in terms of priority such that `position` takes precedence over `velocity` and later fields, `velocity` takes precedence over `acceleration`, and so on. +The first field that has a non-zero value (from top to bottom) defines what valid estimate is required in order to use offboard mode, and the setpoint message(s) that can be used. +For example, if the `acceleration` field is the first non-zero value, then PX4 requires a valid `velocity estimate`, and the setpoint must be specified using the `TrajectorySetpoint` message. -| desired control quantity | position field | velocity field | acceleration field | attitude field | body_rate field | thrust_and_torque field | direct_actuator field | required estimate | required message | -| ------------------------ | -------------- | -------------- | ------------------ | -------------- | --------------- | ------------------------- | --------------------- | ----------------- | ------------------------------------------------------------------------------------------------------------------------------- | -| position (NED) | ✓ | - | - | - | - | - | - | position | [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) | -| velocity (NED) | ✗ | ✓ | - | - | - | - | - | velocity | [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) | -| acceleration (NED) | ✗ | ✗ | ✓ | - | - | - | - | velocity | [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) | -| attitude (FRD) | ✗ | ✗ | ✗ | ✓ | - | - | - | none | [VehicleAttitudeSetpoint](../msg_docs/VehicleAttitudeSetpoint.md) | -| body_rate (FRD) | ✗ | ✗ | ✗ | ✗ | ✓ | - | - | none | [VehicleRatesSetpoint](../msg_docs/VehicleRatesSetpoint.md) | -| thrust and torque (FRD) | ✗ | ✗ | ✗ | ✗ | ✗ | ✓ | - | none | [VehicleThrustSetpoint](../msg_docs/VehicleThrustSetpoint.md) and [VehicleTorqueSetpoint](../msg_docs/VehicleTorqueSetpoint.md) | -| direct motors and servos | ✗ | ✗ | ✗ | ✗ | ✗ | ✗ | ✓ | none | [ActuatorMotors](../msg_docs/ActuatorMotors.md) and [ActuatorServos](../msg_docs/ActuatorServos.md) | +| desired control quantity | position field | velocity field | acceleration field | attitude field | body_rate field | thrust_and_torque field | direct_actuator field | required estimate | required message | +| ------------------------------------------------------- | -------------- | -------------- | ------------------ | -------------- | ------------------------------------ | ----------------------------------------------------------------- | ------------------------------------------ | ----------------- | ------------------------------------------------------------------------------------------------------------------------------- | +| position (NED) | ✓ | - | - | - | - | - | - | position | [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) | +| velocity (NED) | ✗ | ✓ | - | - | - | - | - | velocity | [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) | +| acceleration (NED) | ✗ | ✗ | ✓ | - | - | - | - | velocity | [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) | +| attitude (FRD) | ✗ | ✗ | ✗ | ✓ | - | - | - | none | [VehicleAttitudeSetpoint](../msg_docs/VehicleAttitudeSetpoint.md) | +| body_rate (FRD) | ✗ | ✗ | ✗ | ✗ | ✓ | - | - | none | [VehicleRatesSetpoint](../msg_docs/VehicleRatesSetpoint.md) | +| thrust and torque (FRD) | ✗ | ✗ | ✗ | ✗ | ✗ | ✓ | - | none | [VehicleThrustSetpoint](../msg_docs/VehicleThrustSetpoint.md) and [VehicleTorqueSetpoint](../msg_docs/VehicleTorqueSetpoint.md) | +| direct motors and servos | ✗ | ✗ | ✗ | ✗ | ✗ | ✗ | ✓ | none | [ActuatorMotors](../msg_docs/ActuatorMotors.md) and [ActuatorServos](../msg_docs/ActuatorServos.md) | where ✓ means that the bit is set, ✗ means that the bit is not set and `-` means that the bit is value is irrelevant. -::: info Before using offboard mode with ROS 2, please spend a few minutes understanding the different [frame conventions](../ros2/user_guide.md#ros-2-px4-frame-conventions) that PX4 and ROS 2 use. +:::info +Before using offboard mode with ROS 2, please spend a few minutes understanding the different [frame conventions](../ros2/user_guide.md#ros-2-px4-frame-conventions) that PX4 and ROS 2 use. ::: ### Copter @@ -83,7 +97,8 @@ where ✓ means that the bit is set, ✗ means that the bit is not set a - The following input combination is supported: - - quaternion `q_d` + thrust setpoint `thrust_body`. Non-`NaN` values of `yaw_sp_move_rate` are used as feedforward terms expressed in Earth frame and in \[rad/s\]. + - quaternion `q_d` + thrust setpoint `thrust_body`. + Non-`NaN` values of `yaw_sp_move_rate` are used as feedforward terms expressed in Earth frame and in \[rad/s\]. - The quaternion represents the rotation between the drone body FRD (front, right, down) frame and the NED frame. The thrust is in the drone body FRD frame and expressed in normalized \[-1, 1\] values. @@ -133,11 +148,14 @@ The following MAVLink messages and their particular fields and field values are - The following input combinations are supported: - Position setpoint (only `lat_int`, `lon_int`, `alt`) + - Velocity setpoint (only `vx`, `vy`, `vz`) + - _Thrust_ setpoint (only `afx`, `afy`, `afz`) ::: info -Acceleration setpoint values are mapped to create a normalized thrust setpoint (i.e. acceleration setpoints are not "properly" supported). + Acceleration setpoint values are mapped to create a normalized thrust setpoint (i.e. acceleration setpoints are not "properly" supported). + ::: - Position setpoint **and** velocity setpoint (the velocity setpoint is used as feedforward; it is added to the output of the position controller and the result is used as the input to the velocity controller). @@ -157,12 +175,17 @@ Acceleration setpoint values are mapped to create a normalized thrust setpoint ( - Position setpoint (`x`, `y`, `z` only; velocity and acceleration setpoints are ignored). - - Specify the _type_ of the setpoint in `type_mask` (if these bits are not set the vehicle will fly in a flower-like pattern): ::: info Some of the _setpoint type_ values below are not part of the MAVLink standard for the `type_mask` field. + - Specify the _type_ of the setpoint in `type_mask` (if these bits are not set the vehicle will fly in a flower-like pattern): + ::: info + Some of the _setpoint type_ values below are not part of the MAVLink standard for the `type_mask` field. + ::: The values are: - - 292: Gliding setpoint. This configures TECS to prioritize airspeed over altitude in order to make the vehicle glide when there is no thrust (i.e. pitch is controlled to regulate airspeed). It is equivalent to setting `type_mask` as `POSITION_TARGET_TYPEMASK_Z_IGNORE`, `POSITION_TARGET_TYPEMASK_VZ_IGNORE`, `POSITION_TARGET_TYPEMASK_AZ_IGNORE`. + - 292: Gliding setpoint. + This configures TECS to prioritize airspeed over altitude in order to make the vehicle glide when there is no thrust (i.e. pitch is controlled to regulate airspeed). + It is equivalent to setting `type_mask` as `POSITION_TARGET_TYPEMASK_Z_IGNORE`, `POSITION_TARGET_TYPEMASK_VZ_IGNORE`, `POSITION_TARGET_TYPEMASK_AZ_IGNORE`. - 4096: Takeoff setpoint. - 8192: Land setpoint. - 12288: Loiter setpoint (fly a circle centred on setpoint). @@ -178,7 +201,9 @@ Acceleration setpoint values are mapped to create a normalized thrust setpoint ( - Specify the _type_ of the setpoint in `type_mask` (if these bits are not set the vehicle will fly in a flower-like pattern): - ::: info The _setpoint type_ values below are not part of the MAVLink standard for the `type_mask` field. + ::: info + The _setpoint type_ values below are not part of the MAVLink standard for the `type_mask` field. + ::: The values are: @@ -205,7 +230,9 @@ Acceleration setpoint values are mapped to create a normalized thrust setpoint ( - Specify the _type_ of the setpoint in `type_mask`: - ::: info The _setpoint type_ values below are not part of the MAVLink standard for the `type_mask` field. :: + ::: info + The _setpoint type_ values below are not part of the MAVLink standard for the `type_mask` field. + :: The values are: @@ -219,7 +246,9 @@ Acceleration setpoint values are mapped to create a normalized thrust setpoint ( - The following input combinations are supported (in `type_mask`): - Position setpoint (only `lat_int`, `lon_int`, `alt`) - - Specify the _type_ of the setpoint in `type_mask` (not part of the MAVLink standard). The values are: + + - Specify the _type_ of the setpoint in `type_mask` (not part of the MAVLink standard). + The values are: - Following bits not set then normal behaviour. - 12288: Loiter setpoint (vehicle stops when close enough to setpoint). @@ -228,21 +257,23 @@ Acceleration setpoint values are mapped to create a normalized thrust setpoint ( - [SET_ATTITUDE_TARGET](https://mavlink.io/en/messages/common.html#SET_ATTITUDE_TARGET) - The following input combinations are supported: - - Attitude/orientation (`SET_ATTITUDE_TARGET.q`) with thrust setpoint (`SET_ATTITUDE_TARGET.thrust`). ::: info -Only the yaw setting is actually used/extracted. + - Attitude/orientation (`SET_ATTITUDE_TARGET.q`) with thrust setpoint (`SET_ATTITUDE_TARGET.thrust`). + ::: info + Only the yaw setting is actually used/extracted. + ::: ## Offboard Parameters _Offboard mode_ is affected by the following parameters: -| Parameter | Description | -| ------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | -| [COM_OF_LOSS_T](../advanced_config/parameter_reference.md#COM_OF_LOSS_T) | Time-out (in seconds) to wait when offboard connection is lost before triggering offboard lost failsafe (`COM_OBL_RC_ACT`) | -| [COM_OBL_RC_ACT](../advanced_config/parameter_reference.md#COM_OBL_RC_ACT) | Flight mode to switch to if offboard control is lost (Values are - `0`: _Position_, `1`: _Altitude_, `2`: _Manual_, `3`: *Return, `4`: *Land\*). | -| [COM_RC_OVERRIDE](../advanced_config/parameter_reference.md#COM_RC_OVERRIDE) | Controls whether stick movement on a multicopter (or VTOL in MC mode) causes a mode change to [Position mode](../flight_modes_mc/position.md). This is not enabled for offboard mode by default. | -| [COM_RC_STICK_OV](../advanced_config/parameter_reference.md#COM_RC_STICK_OV) | The amount of stick movement that causes a transition to [Position mode](../flight_modes_mc/position.md) (if [COM_RC_OVERRIDE](#COM_RC_OVERRIDE) is enabled). | -| [COM_RCL_EXCEPT](../advanced_config/parameter_reference.md#COM_RCL_EXCEPT) | Specify modes in which RC loss is ignored and the failsafe action not triggered. Set bit `2` to ignore RC loss in Offboard mode. | +| Parameter | Description | +| ----------------------------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [COM_OF_LOSS_T](../advanced_config/parameter_reference.md#COM_OF_LOSS_T) | Time-out (in seconds) to wait when offboard connection is lost before triggering offboard lost failsafe (`COM_OBL_RC_ACT`) | +| [COM_OBL_RC_ACT](../advanced_config/parameter_reference.md#COM_OBL_RC_ACT) | Flight mode to switch to if offboard control is lost (Values are - `0`: _Position_, `1`: _Altitude_, `2`: _Manual_, `3`: \*Return, `4`: \*Land\*). | +| [COM_RC_OVERRIDE](../advanced_config/parameter_reference.md#COM_RC_OVERRIDE) | Controls whether stick movement on a multicopter (or VTOL in MC mode) causes a mode change to [Position mode](../flight_modes_mc/position.md). This is not enabled for offboard mode by default. | +| [COM_RC_STICK_OV](../advanced_config/parameter_reference.md#COM_RC_STICK_OV) | The amount of stick movement that causes a transition to [Position mode](../flight_modes_mc/position.md) (if [COM_RC_OVERRIDE](#COM_RC_OVERRIDE) is enabled). | +| [COM_RCL_EXCEPT](../advanced_config/parameter_reference.md#COM_RCL_EXCEPT) | Specify modes in which RC loss is ignored and the failsafe action not triggered. Set bit `2` to ignore RC loss in Offboard mode. | ## Developer Resources