Compare commits

...

17 Commits

Author SHA1 Message Date
Hamish Willee d4d3f8e797 Improve intro, I hope 2025-06-12 18:31:37 +10:00
Hamish Willee bad860269d Methodical uorb documentation 2025-06-12 08:34:40 +10:00
Crowdin Bot e0b5342e98 New Crowdin translations - zh-CN 2025-06-12 08:34:11 +10:00
Crowdin Bot f9c36b8235 New Crowdin translations - uk 2025-06-12 08:33:00 +10:00
Crowdin Bot 5af5bdb478 New Crowdin translations - ko 2025-06-12 08:32:09 +10:00
Hamish Willee dc8e313c0d Fix up alt _sidebar 2025-06-12 08:26:34 +10:00
Hamish Willee 53ae458fb5 Update dds_yaml links to the markdown doc 2025-06-12 08:26:34 +10:00
PX4BuildBot cd2e970249 Add dds_topics 2025-06-12 08:26:34 +10:00
Alexis Guijarro 26499b3c8b 3DR Control Zero H7 OEM RevG: MTD driver fix (#25015) 2025-06-11 12:43:00 -04:00
Peter van der Perk 0fe8738ed9 msp_osd: Add VTX config, stick commands and arming status
- Adds MSPv1 rx parsing to fetch VTX config
 - Allows to inspect and change VTX channel through CLI
 - Forward MSP_RC for stick commands osd
 - Forward MSP_STATUS for arming status for PIT and LP mode
2025-06-11 11:32:32 -04:00
Beat Küng 50626f6848 VehicleStatus.msg: restore VEHICLE_TYPE_* indexes
This was changed in 7cb6464cfb and broke flight review
(https://github.com/PX4/flight_review/issues/310)
2025-06-11 11:24:47 -04:00
chfriedrich98 d348bf4828 mecanum: centralize mode management, resets and checks 2025-06-11 14:17:23 +02:00
chfriedrich98 f0c15af426 mecanum: update position controller 2025-06-11 14:17:23 +02:00
chfriedrich98 5e9322899b mecanum: seperate actuator control 2025-06-11 14:17:23 +02:00
Hamish Willee 85c2f8ebbb Clarify how the queue works 2025-06-11 19:06:14 +10:00
Hamish Willee 412e5169e9 Add ORB_QUEUE_LENGTH info 2025-06-11 19:06:14 +10:00
Jacob Dahl 74570d5abe docs: ekf replay: require log from boot (#24675) 2025-06-10 11:11:34 -06:00
67 changed files with 3800 additions and 1541 deletions
@@ -132,6 +132,7 @@ ENTRY(_stext)
*/
EXTERN(abort)
EXTERN(_bootdelay_signature)
EXTERN(board_get_manifest)
SECTIONS
{
@@ -48,6 +48,7 @@ else()
i2c.cpp
init.c
led.c
mtd.cpp
spi.cpp
timer_config.cpp
usb.c
@@ -0,0 +1,76 @@
/****************************************************************************
*
* Copyright (C) 2025 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include <nuttx/spi/spi.h>
#include <px4_platform_common/px4_manifest.h>
// KiB BS nB
static const px4_mft_device_t spi2 = { // FM25V01A on FMUM native: 32K X 8, emulated as (1024 Blocks of 32)
.bus_type = px4_mft_device_t::SPI,
.devid = SPIDEV_FLASH(0)
};
static const px4_mtd_entry_t fmum_fram = {
.device = &spi2,
.npart = 1,
.partd = {
{
.type = MTD_PARAMETERS,
.path = "/fs/mtd_params",
.nblocks = (32768 / (1 << CONFIG_RAMTRON_EMULATE_PAGE_SHIFT))
},
},
};
static const px4_mtd_manifest_t board_mtd_config = {
.nconfigs = 1,
.entries = {
&fmum_fram
}
};
static const px4_mft_entry_s mtd_mft = {
.type = MTD,
.pmft = (void *) &board_mtd_config,
};
static const px4_mft_s mft = {
.nmft = 1,
.mfts = {
&mtd_mft
}
};
const px4_mft_s *board_get_manifest(void)
{
return &mft;
}
+1
View File
@@ -730,6 +730,7 @@
- [Protocols/Microservices](mavlink/protocols.md)
- [Standard Modes Protocol](mavlink/standard_modes.md)
- [uXRCE-DDS (PX4-ROS 2/DDS Bridge)](middleware/uxrce_dds.md)
- [UORB Bridged to ROS 2](middleware/dds_topics.md)
- [Modules & Commands](modules/modules_main.md)
- [Autotune](modules/modules_autotune.md)
- [Commands](modules/modules_command.md)
+18 -8
View File
@@ -490,12 +490,17 @@
- [Versioned](/msg_docs/versioned_messages.md)
- [ActuatorMotors](/msg_docs/ActuatorMotors.md)
- [ActuatorServos](/msg_docs/ActuatorServos.md)
- [AirspeedValidated](/msg_docs/AirspeedValidated.md)
- [ArmingCheckReply](/msg_docs/ArmingCheckReply.md)
- [ArmingCheckRequest](/msg_docs/ArmingCheckRequest.md)
- [BatteryStatus](/msg_docs/BatteryStatus.md)
- [ConfigOverrides](/msg_docs/ConfigOverrides.md)
- [FixedWingLateralSetpoint](/msg_docs/FixedWingLateralSetpoint.md)
- [FixedWingLongitudinalSetpoint](/msg_docs/FixedWingLongitudinalSetpoint.md)
- [GotoSetpoint](/msg_docs/GotoSetpoint.md)
- [HomePosition](/msg_docs/HomePosition.md)
- [LateralControlConfiguration](/msg_docs/LateralControlConfiguration.md)
- [LongitudinalControlConfiguration](/msg_docs/LongitudinalControlConfiguration.md)
- [ManualControlSetpoint](/msg_docs/ManualControlSetpoint.md)
- [ModeCompleted](/msg_docs/ModeCompleted.md)
- [RegisterExtComponentReply](/msg_docs/RegisterExtComponentReply.md)
@@ -524,10 +529,8 @@
- [ActuatorTest](/msg_docs/ActuatorTest.md)
- [AdcReport](/msg_docs/AdcReport.md)
- [Airspeed](/msg_docs/Airspeed.md)
- [AirspeedValidated](/msg_docs/AirspeedValidated.md)
- [AirspeedWind](/msg_docs/AirspeedWind.md)
- [AutotuneAttitudeControlStatus](/msg_docs/AutotuneAttitudeControlStatus.md)
- [Buffer128](/msg_docs/Buffer128.md)
- [ButtonEvent](/msg_docs/ButtonEvent.md)
- [CameraCapture](/msg_docs/CameraCapture.md)
- [CameraStatus](/msg_docs/CameraStatus.md)
@@ -566,6 +569,9 @@
- [FailsafeFlags](/msg_docs/FailsafeFlags.md)
- [FailureDetectorStatus](/msg_docs/FailureDetectorStatus.md)
- [FigureEightStatus](/msg_docs/FigureEightStatus.md)
- [FixedWingLateralGuidanceStatus](/msg_docs/FixedWingLateralGuidanceStatus.md)
- [FixedWingLateralStatus](/msg_docs/FixedWingLateralStatus.md)
- [FixedWingRunwayControl](/msg_docs/FixedWingRunwayControl.md)
- [FlightPhaseEstimation](/msg_docs/FlightPhaseEstimation.md)
- [FollowTarget](/msg_docs/FollowTarget.md)
- [FollowTargetEstimator](/msg_docs/FollowTargetEstimator.md)
@@ -618,7 +624,6 @@
- [NavigatorMissionItem](/msg_docs/NavigatorMissionItem.md)
- [NavigatorStatus](/msg_docs/NavigatorStatus.md)
- [NormalizedUnsignedSetpoint](/msg_docs/NormalizedUnsignedSetpoint.md)
- [NpfgStatus](/msg_docs/NpfgStatus.md)
- [ObstacleDistance](/msg_docs/ObstacleDistance.md)
- [OffboardControlMode](/msg_docs/OffboardControlMode.md)
- [OnboardComputerStatus](/msg_docs/OnboardComputerStatus.md)
@@ -654,13 +659,12 @@
- [RcParameterMap](/msg_docs/RcParameterMap.md)
- [RoverAttitudeSetpoint](/msg_docs/RoverAttitudeSetpoint.md)
- [RoverAttitudeStatus](/msg_docs/RoverAttitudeStatus.md)
- [RoverMecanumGuidanceStatus](/msg_docs/RoverMecanumGuidanceStatus.md)
- [RoverMecanumSetpoint](/msg_docs/RoverMecanumSetpoint.md)
- [RoverMecanumStatus](/msg_docs/RoverMecanumStatus.md)
- [RoverPositionSetpoint](/msg_docs/RoverPositionSetpoint.md)
- [RoverRateSetpoint](/msg_docs/RoverRateSetpoint.md)
- [RoverRateStatus](/msg_docs/RoverRateStatus.md)
- [RoverSteeringSetpoint](/msg_docs/RoverSteeringSetpoint.md)
- [RoverThrottleSetpoint](/msg_docs/RoverThrottleSetpoint.md)
- [RoverVelocitySetpoint](/msg_docs/RoverVelocitySetpoint.md)
- [RoverVelocityStatus](/msg_docs/RoverVelocityStatus.md)
- [Rpm](/msg_docs/Rpm.md)
- [RtlStatus](/msg_docs/RtlStatus.md)
@@ -692,6 +696,7 @@
- [TelemetryStatus](/msg_docs/TelemetryStatus.md)
- [TiltrotorExtraControls](/msg_docs/TiltrotorExtraControls.md)
- [TimesyncStatus](/msg_docs/TimesyncStatus.md)
- [TrajectorySetpoint6dof](/msg_docs/TrajectorySetpoint6dof.md)
- [TransponderReport](/msg_docs/TransponderReport.md)
- [TuneControl](/msg_docs/TuneControl.md)
- [UavcanParameterRequest](/msg_docs/UavcanParameterRequest.md)
@@ -715,14 +720,18 @@
- [WheelEncoders](/msg_docs/WheelEncoders.md)
- [Wind](/msg_docs/Wind.md)
- [YawEstimatorStatus](/msg_docs/YawEstimatorStatus.md)
- [AirspeedValidatedV0](/msg_docs/AirspeedValidatedV0.md)
- [VehicleAttitudeSetpointV0](/msg_docs/VehicleAttitudeSetpointV0.md)
- [VehicleStatusV0](/msg_docs/VehicleStatusV0.md)
- [MAVLink Messaging](/middleware/mavlink.md)
- [MAVLink Messaging](/mavlink/index.md)
- [Adding Messages](/mavlink/adding_messages.md)
- [Streaming Messages](/mavlink/streaming_messages.md)
- [Receiving Messages](/mavlink/receiving_messages.md)
- [Custom MAVLink Messages](/mavlink/custom_messages.md)
- [Standard Modes Protocol](/mavlink/standard_modes.md)
- [Protocols/Microservices](/mavlink/protocols.md)
- [Standard Modes Protocol](/mavlink/standard_modes.md)
- [uXRCE-DDS (PX4-ROS 2/DDS Bridge)](/middleware/uxrce_dds.md)
- [UORB Bridged to ROS 2](/middleware/dds_topics.md)
- [Modules & Commands](/modules/modules_main.md)
- [Autotune](/modules/modules_autotune.md)
- [Commands](/modules/modules_command.md)
@@ -848,6 +857,7 @@
- [Licenses](/contribute/licenses.md)
- [Releases](/releases/index.md)
- [main (alpha)](/releases/main.md)
- [1.16 (release candidate)](/releases/1.16.md)
- [1.15 (stable)](/releases/1.15.md)
- [1.14](/releases/1.14.md)
- [1.13](/releases/1.13.md)
@@ -212,7 +212,7 @@ The steps are:
type: px4_msgs::msg::ObstacleDistance
```
For more information see [DDS Topics YAML](../middleware/uxrce_dds.md#dds-topics-yaml) in _uXRCE-DDS (PX4-ROS 2/DDS Bridge)_.
For more information see [DDS Topics YAML](../middleware/uxrce_dds.md#dds-topics-yaml) in [uXRCE-DDS](../middleware/uxrce_dds.md) (PX4-ROS 2/DDS Bridge)_.
3. Open PlotJuggler and navigate to the **Tools > Reactive Script Editor** section.
In the **Script Editor** tab, add following scripts in the appropriate sections:
+3 -3
View File
@@ -94,13 +94,13 @@ Exporting the messages allows ROS 2 and the uXRCE-DDS agent to be independent of
While `px4_msgs` has messages for all uORB topics in PX4, not all messages in `px4_msgs` are available to ROS 2/PlotJuggler by default.
The set that are available must be built into the client running on PX4.
These are defined in [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml).
These are defined in [dds_topics.yaml](../middleware/dds_topics.md).
The instructions below explain the changes needed to monitor topics that are not available by default.
### Missing Topics
If a normal uORB topic is not available in PlotJuggler you will need to modify the [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) to include the topic and rebuild PX4.
If a normal uORB topic is not available in PlotJuggler you will need to modify the [dds_topics.yaml](../middleware/dds_topics.md) ([source](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml)) to include the topic and rebuild PX4.
If working with real hardware you will need to build and [install](../config/firmware.md#installing-px4-main-beta-or-custom-firmware) custom firmware after changing the YAML file.
@@ -120,7 +120,7 @@ cd ~/ros2_ws/ && colcon build
### Custom Topics
After defining the topic, follow the instructions above to add the topic to [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), and export the new message into your ROS 2 workspace.
After defining the topic, follow the instructions above to add the topic to [dds_topics.yaml](../middleware/dds_topics.md), and export the new message into your ROS 2 workspace.
## See also
+1 -2
View File
@@ -126,8 +126,7 @@ In EKF2 mode, the replay will automatically create the ORB publisher rules descr
To perform an EKF2 replay:
- Record the original log.
Optionally set `SDLOG_MODE` to `1` to log from boot.
- Record the original log with `SDLOG_MODE` set to `1` to log from boot.
- In addition to the `replay` environment variable, set `replay_mode` to `ekf2`:
+276
View File
@@ -0,0 +1,276 @@
# dds_topics.yaml — PX4 Topics Exposed to ROS 2
::: info
This document is [auto-generated](https://github.com/PX4/PX4-Autopilot/blob/main/Tools/msg/generate_msg_docs.py) from the source code.
:::
The [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) file specifies which uORB message definitions are compiled into the [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) module when [PX4 is built](../middleware/uxrce_dds.md#code-generation), and hence which topics are available for ROS 2 applications to subscribe or publish (by default).
This document shows a markdown-rendered version of [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), listing the publications, subscriptions, and so on.
## Publications
Topic | Type| Rate Limit
--- | --- | ---
`/fmu/out/register_ext_component_reply` | [px4_msgs::msg::RegisterExtComponentReply](../msg_docs/RegisterExtComponentReply.md) |
`/fmu/out/arming_check_request` | [px4_msgs::msg::ArmingCheckRequest](../msg_docs/ArmingCheckRequest.md) | 5.0
`/fmu/out/mode_completed` | [px4_msgs::msg::ModeCompleted](../msg_docs/ModeCompleted.md) | 50.0
`/fmu/out/battery_status` | [px4_msgs::msg::BatteryStatus](../msg_docs/BatteryStatus.md) | 1.0
`/fmu/out/collision_constraints` | [px4_msgs::msg::CollisionConstraints](../msg_docs/CollisionConstraints.md) | 50.0
`/fmu/out/estimator_status_flags` | [px4_msgs::msg::EstimatorStatusFlags](../msg_docs/EstimatorStatusFlags.md) | 5.0
`/fmu/out/failsafe_flags` | [px4_msgs::msg::FailsafeFlags](../msg_docs/FailsafeFlags.md) | 5.0
`/fmu/out/manual_control_setpoint` | [px4_msgs::msg::ManualControlSetpoint](../msg_docs/ManualControlSetpoint.md) | 25.0
`/fmu/out/message_format_response` | [px4_msgs::msg::MessageFormatResponse](../msg_docs/MessageFormatResponse.md) |
`/fmu/out/position_setpoint_triplet` | [px4_msgs::msg::PositionSetpointTriplet](../msg_docs/PositionSetpointTriplet.md) | 5.0
`/fmu/out/sensor_combined` | [px4_msgs::msg::SensorCombined](../msg_docs/SensorCombined.md) |
`/fmu/out/timesync_status` | [px4_msgs::msg::TimesyncStatus](../msg_docs/TimesyncStatus.md) | 10.0
`/fmu/out/vehicle_land_detected` | [px4_msgs::msg::VehicleLandDetected](../msg_docs/VehicleLandDetected.md) | 5.0
`/fmu/out/vehicle_attitude` | [px4_msgs::msg::VehicleAttitude](../msg_docs/VehicleAttitude.md) |
`/fmu/out/vehicle_control_mode` | [px4_msgs::msg::VehicleControlMode](../msg_docs/VehicleControlMode.md) | 50.0
`/fmu/out/vehicle_command_ack` | [px4_msgs::msg::VehicleCommandAck](../msg_docs/VehicleCommandAck.md) |
`/fmu/out/vehicle_global_position` | [px4_msgs::msg::VehicleGlobalPosition](../msg_docs/VehicleGlobalPosition.md) | 50.0
`/fmu/out/vehicle_gps_position` | [px4_msgs::msg::SensorGps](../msg_docs/SensorGps.md) | 50.0
`/fmu/out/vehicle_local_position` | [px4_msgs::msg::VehicleLocalPosition](../msg_docs/VehicleLocalPosition.md) | 50.0
`/fmu/out/vehicle_odometry` | [px4_msgs::msg::VehicleOdometry](../msg_docs/VehicleOdometry.md) |
`/fmu/out/vehicle_status` | [px4_msgs::msg::VehicleStatus](../msg_docs/VehicleStatus.md) | 5.0
`/fmu/out/airspeed_validated` | [px4_msgs::msg::AirspeedValidated](../msg_docs/AirspeedValidated.md) | 50.0
`/fmu/out/vtol_vehicle_status` | [px4_msgs::msg::VtolVehicleStatus](../msg_docs/VtolVehicleStatus.md) |
`/fmu/out/home_position` | [px4_msgs::msg::HomePosition](../msg_docs/HomePosition.md) | 5.0
## Subscriptions
Topic | Type
--- | ---
/fmu/in/register_ext_component_request | [px4_msgs::msg::RegisterExtComponentRequest](../msg_docs/RegisterExtComponentRequest.md)
/fmu/in/unregister_ext_component | [px4_msgs::msg::UnregisterExtComponent](../msg_docs/UnregisterExtComponent.md)
/fmu/in/config_overrides_request | [px4_msgs::msg::ConfigOverrides](../msg_docs/ConfigOverrides.md)
/fmu/in/arming_check_reply | [px4_msgs::msg::ArmingCheckReply](../msg_docs/ArmingCheckReply.md)
/fmu/in/message_format_request | [px4_msgs::msg::MessageFormatRequest](../msg_docs/MessageFormatRequest.md)
/fmu/in/mode_completed | [px4_msgs::msg::ModeCompleted](../msg_docs/ModeCompleted.md)
/fmu/in/config_control_setpoints | [px4_msgs::msg::VehicleControlMode](../msg_docs/VehicleControlMode.md)
/fmu/in/distance_sensor | [px4_msgs::msg::DistanceSensor](../msg_docs/DistanceSensor.md)
/fmu/in/manual_control_input | [px4_msgs::msg::ManualControlSetpoint](../msg_docs/ManualControlSetpoint.md)
/fmu/in/offboard_control_mode | [px4_msgs::msg::OffboardControlMode](../msg_docs/OffboardControlMode.md)
/fmu/in/onboard_computer_status | [px4_msgs::msg::OnboardComputerStatus](../msg_docs/OnboardComputerStatus.md)
/fmu/in/obstacle_distance | [px4_msgs::msg::ObstacleDistance](../msg_docs/ObstacleDistance.md)
/fmu/in/sensor_optical_flow | [px4_msgs::msg::SensorOpticalFlow](../msg_docs/SensorOpticalFlow.md)
/fmu/in/goto_setpoint | [px4_msgs::msg::GotoSetpoint](../msg_docs/GotoSetpoint.md)
/fmu/in/telemetry_status | [px4_msgs::msg::TelemetryStatus](../msg_docs/TelemetryStatus.md)
/fmu/in/trajectory_setpoint | [px4_msgs::msg::TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md)
/fmu/in/vehicle_attitude_setpoint | [px4_msgs::msg::VehicleAttitudeSetpoint](../msg_docs/VehicleAttitudeSetpoint.md)
/fmu/in/vehicle_mocap_odometry | [px4_msgs::msg::VehicleOdometry](../msg_docs/VehicleOdometry.md)
/fmu/in/vehicle_rates_setpoint | [px4_msgs::msg::VehicleRatesSetpoint](../msg_docs/VehicleRatesSetpoint.md)
/fmu/in/vehicle_visual_odometry | [px4_msgs::msg::VehicleOdometry](../msg_docs/VehicleOdometry.md)
/fmu/in/vehicle_command | [px4_msgs::msg::VehicleCommand](../msg_docs/VehicleCommand.md)
/fmu/in/vehicle_command_mode_executor | [px4_msgs::msg::VehicleCommand](../msg_docs/VehicleCommand.md)
/fmu/in/vehicle_thrust_setpoint | [px4_msgs::msg::VehicleThrustSetpoint](../msg_docs/VehicleThrustSetpoint.md)
/fmu/in/vehicle_torque_setpoint | [px4_msgs::msg::VehicleTorqueSetpoint](../msg_docs/VehicleTorqueSetpoint.md)
/fmu/in/actuator_motors | [px4_msgs::msg::ActuatorMotors](../msg_docs/ActuatorMotors.md)
/fmu/in/actuator_servos | [px4_msgs::msg::ActuatorServos](../msg_docs/ActuatorServos.md)
/fmu/in/aux_global_position | [px4_msgs::msg::VehicleGlobalPosition](../msg_docs/VehicleGlobalPosition.md)
/fmu/in/fixed_wing_longitudinal_setpoint | [px4_msgs::msg::FixedWingLongitudinalSetpoint](../msg_docs/FixedWingLongitudinalSetpoint.md)
/fmu/in/fixed_wing_lateral_setpoint | [px4_msgs::msg::FixedWingLateralSetpoint](../msg_docs/FixedWingLateralSetpoint.md)
/fmu/in/longitudinal_control_configuration | [px4_msgs::msg::LongitudinalControlConfiguration](../msg_docs/LongitudinalControlConfiguration.md)
/fmu/in/lateral_control_configuration | [px4_msgs::msg::LateralControlConfiguration](../msg_docs/LateralControlConfiguration.md)
## Subscriptions Multi
None
## Not Exported
These messages are not listed in the yaml file.
They are not build into the module, and hence are neither published or subscribed.
::: details See messages
- [SensorCorrection](../msg_docs/SensorCorrection.md)
- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md)
- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md)
- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md)
- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md)
- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md)
- [Px4ioStatus](../msg_docs/Px4ioStatus.md)
- [SatelliteInfo](../msg_docs/SatelliteInfo.md)
- [GeofenceResult](../msg_docs/GeofenceResult.md)
- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md)
- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md)
- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md)
- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md)
- [EventV0](../msg_docs/EventV0.md)
- [QshellRetval](../msg_docs/QshellRetval.md)
- [RoverThrottleSetpoint](../msg_docs/RoverThrottleSetpoint.md)
- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md)
- [RcChannels](../msg_docs/RcChannels.md)
- [SensorAccel](../msg_docs/SensorAccel.md)
- [GimbalDeviceAttitudeStatus](../msg_docs/GimbalDeviceAttitudeStatus.md)
- [EscStatus](../msg_docs/EscStatus.md)
- [RoverAttitudeSetpoint](../msg_docs/RoverAttitudeSetpoint.md)
- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md)
- [AirspeedWind](../msg_docs/AirspeedWind.md)
- [InputRc](../msg_docs/InputRc.md)
- [GpioIn](../msg_docs/GpioIn.md)
- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md)
- [VehicleImu](../msg_docs/VehicleImu.md)
- [Event](../msg_docs/Event.md)
- [SensorUwb](../msg_docs/SensorUwb.md)
- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md)
- [DatamanResponse](../msg_docs/DatamanResponse.md)
- [OrbTest](../msg_docs/OrbTest.md)
- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md)
- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md)
- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md)
- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md)
- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md)
- [TakeoffStatus](../msg_docs/TakeoffStatus.md)
- [UlogStreamAck](../msg_docs/UlogStreamAck.md)
- [OrbTestLarge](../msg_docs/OrbTestLarge.md)
- [RoverSteeringSetpoint](../msg_docs/RoverSteeringSetpoint.md)
- [CameraCapture](../msg_docs/CameraCapture.md)
- [VehicleRoi](../msg_docs/VehicleRoi.md)
- [ActuatorArmed](../msg_docs/ActuatorArmed.md)
- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md)
- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md)
- [GeofenceStatus](../msg_docs/GeofenceStatus.md)
- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md)
- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md)
- [PowerMonitor](../msg_docs/PowerMonitor.md)
- [RoverVelocityStatus](../msg_docs/RoverVelocityStatus.md)
- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md)
- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md)
- [TecsStatus](../msg_docs/TecsStatus.md)
- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md)
- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md)
- [Ping](../msg_docs/Ping.md)
- [LedControl](../msg_docs/LedControl.md)
- [Wind](../msg_docs/Wind.md)
- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md)
- [ActuatorTest](../msg_docs/ActuatorTest.md)
- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md)
- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md)
- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md)
- [Gripper](../msg_docs/Gripper.md)
- [SensorMag](../msg_docs/SensorMag.md)
- [DebugValue](../msg_docs/DebugValue.md)
- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md)
- [RcParameterMap](../msg_docs/RcParameterMap.md)
- [LandingGear](../msg_docs/LandingGear.md)
- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md)
- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md)
- [UlogStream](../msg_docs/UlogStream.md)
- [GimbalControls](../msg_docs/GimbalControls.md)
- [RoverRateSetpoint](../msg_docs/RoverRateSetpoint.md)
- [LogMessage](../msg_docs/LogMessage.md)
- [RoverVelocitySetpoint](../msg_docs/RoverVelocitySetpoint.md)
- [GpioOut](../msg_docs/GpioOut.md)
- [TaskStackInfo](../msg_docs/TaskStackInfo.md)
- [VelocityLimits](../msg_docs/VelocityLimits.md)
- [MagWorkerData](../msg_docs/MagWorkerData.md)
- [ParameterUpdate](../msg_docs/ParameterUpdate.md)
- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md)
- [SensorBaro](../msg_docs/SensorBaro.md)
- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md)
- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md)
- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md)
- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md)
- [Rpm](../msg_docs/Rpm.md)
- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md)
- [MountOrientation](../msg_docs/MountOrientation.md)
- [ActionRequest](../msg_docs/ActionRequest.md)
- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md)
- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md)
- [LoggerStatus](../msg_docs/LoggerStatus.md)
- [GeneratorStatus](../msg_docs/GeneratorStatus.md)
- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md)
- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md)
- [LandingTargetPose](../msg_docs/LandingTargetPose.md)
- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md)
- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md)
- [OrbitStatus](../msg_docs/OrbitStatus.md)
- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md)
- [EstimatorStatus](../msg_docs/EstimatorStatus.md)
- [DatamanRequest](../msg_docs/DatamanRequest.md)
- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md)
- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md)
- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md)
- [Cpuload](../msg_docs/Cpuload.md)
- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md)
- [RoverRateStatus](../msg_docs/RoverRateStatus.md)
- [EscReport](../msg_docs/EscReport.md)
- [DebugArray](../msg_docs/DebugArray.md)
- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md)
- [SensorHygrometer](../msg_docs/SensorHygrometer.md)
- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md)
- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md)
- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md)
- [QshellReq](../msg_docs/QshellReq.md)
- [CameraStatus](../msg_docs/CameraStatus.md)
- [GpsInjectData](../msg_docs/GpsInjectData.md)
- [FigureEightStatus](../msg_docs/FigureEightStatus.md)
- [TransponderReport](../msg_docs/TransponderReport.md)
- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md)
- [MavlinkLog](../msg_docs/MavlinkLog.md)
- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md)
- [FuelTankStatus](../msg_docs/FuelTankStatus.md)
- [Mission](../msg_docs/Mission.md)
- [PositionSetpoint](../msg_docs/PositionSetpoint.md)
- [MissionResult](../msg_docs/MissionResult.md)
- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md)
- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md)
- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md)
- [DifferentialPressure](../msg_docs/DifferentialPressure.md)
- [CellularStatus](../msg_docs/CellularStatus.md)
- [GpsDump](../msg_docs/GpsDump.md)
- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md)
- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md)
- [NavigatorStatus](../msg_docs/NavigatorStatus.md)
- [RoverPositionSetpoint](../msg_docs/RoverPositionSetpoint.md)
- [FollowTarget](../msg_docs/FollowTarget.md)
- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md)
- [EstimatorStates](../msg_docs/EstimatorStates.md)
- [SensorGyro](../msg_docs/SensorGyro.md)
- [SensorAirflow](../msg_docs/SensorAirflow.md)
- [ButtonEvent](../msg_docs/ButtonEvent.md)
- [DebugKeyValue](../msg_docs/DebugKeyValue.md)
- [GpioConfig](../msg_docs/GpioConfig.md)
- [CameraTrigger](../msg_docs/CameraTrigger.md)
- [LandingGearWheel](../msg_docs/LandingGearWheel.md)
- [VehicleConstraints](../msg_docs/VehicleConstraints.md)
- [HealthReport](../msg_docs/HealthReport.md)
- [PowerButtonState](../msg_docs/PowerButtonState.md)
- [RadioStatus](../msg_docs/RadioStatus.md)
- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md)
- [EstimatorBias](../msg_docs/EstimatorBias.md)
- [DebugVect](../msg_docs/DebugVect.md)
- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md)
- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md)
- [PpsCapture](../msg_docs/PpsCapture.md)
- [SensorSelection](../msg_docs/SensorSelection.md)
- [SystemPower](../msg_docs/SystemPower.md)
- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md)
- [SensorGyroFft](../msg_docs/SensorGyroFft.md)
- [VehicleAirData](../msg_docs/VehicleAirData.md)
- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md)
- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md)
- [GpioRequest](../msg_docs/GpioRequest.md)
- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md)
- [RtlStatus](../msg_docs/RtlStatus.md)
- [Airspeed](../msg_docs/Airspeed.md)
- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md)
- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md)
- [IrlockReport](../msg_docs/IrlockReport.md)
- [HeaterStatus](../msg_docs/HeaterStatus.md)
- [AdcReport](../msg_docs/AdcReport.md)
- [PwmInput](../msg_docs/PwmInput.md)
- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md)
- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md)
- [OrbTestMedium](../msg_docs/OrbTestMedium.md)
- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md)
- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md)
- [TuneControl](../msg_docs/TuneControl.md)
- [WheelEncoders](../msg_docs/WheelEncoders.md)
- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md)
- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md)
- [SensorsStatus](../msg_docs/SensorsStatus.md)
:::
+248 -19
View File
@@ -1,11 +1,35 @@
# uORB Messaging
The Micro Object Request Broker (uORB) is PX4s low-latency asynchronous `publish()` / `subscribe()` messaging API for inter-thread/inter-process communication.
It allows the different modules of the system to communicate effectively, while still being loosely coupled, and hence easily replaced.
## Introduction
The uORB is an asynchronous `publish()` / `subscribe()` messaging API used for inter-thread/inter-process communication.
PX4 modules communicate using uORB _topics_.
A topic represents a communication channel for sending _messages_ between a publisher module and one or more subscriber modules.
A module that is interested in receiving messages can subscribe to a topic and use it to check for, and read, new messages.
A module that wants to send messages to a particular topic (and hence all subscribers) must _advertise_ that it is going to do so, and can then _publish_ messages when it has new data.
A topic behaves like a queue to which publishers write, and from which subscribers read.
By default he queue can only buffer a single message, which may be overwritten if the publisher writes new message data before subscribers can read it.
The [queue size may be increased](#uorb-buffer-length-orb-queue-length) in the rare cases when subscribers really need to receive every message.
A message is a discrete sample of data that can be published/subscribed via a topic.
The message fields, the constants that can be used with those fields, and the topic(s) to which the message can be published/subscribed are defined in a uORB message definition file.
By default a single topic is automatically created for each message definition file, which is created by `underscore_snake_casing` the (CamelCase) message definition file name.
For example, topic `battery_status` is automatically created for the `BatteryStatus.msg`.
This is generally what you want if the message is always about the same kind of data (batteries in this case) and so all the subscribers will be interested in the same messages.
Sometimes the same message structure can be used to represent data from different kinds of sources, which will have different sets of interested publishers and subscribers.
In this case the topics need to be explicitly declared.
For example the [VehicleGlobalPosition.msg](../msg_docs/VehicleGlobalPosition.md) can be used for sending messages about global position from an estimator, GNSS, or an external source: the fields are the same, but the source and subscribers of the data may be different.
uORB also provides a mechanism to publish multiple independent instances of the same topic.
This is useful, for example, if the system has several sensors of the same type.
uORB is implemented in the [`uorb` module](../modules/modules_communication.md#uorb).
It is started automatically (with `uorb start`) early in the PX4 boot sequence, as many applications depend on it.
The module is started automatically (with `uorb start`) early in the PX4 boot sequence, as many applications depend on it.
Unit tests can be started with `uorb_tests`.
This document explains how to add uORB message definitions and their corresponding topic(s), how to use reference a topic in code, and how to view topics as they change in PX4.
@@ -42,31 +66,31 @@ In code you refer to the topic using its id, which in this example would be: `OR
## Message Definitions
The message definition should start with a descriptive _comment_ that outlines its purpose (a comment starts with the `#` symbol and goes to the end of the line).
Every message should start with a [message description](#message-description) that outlines its purpose (a comment starts with the `#` symbol and goes to the end of the line).
The message will then define one or more fields, which are defined with a _type_, such as `bool`, `uint8`, and `float32`, followed by a _name_.
By convention, each field is followed by a descriptive _comment_, which is any text from the `#` symbol to the end of the line.
::: warning
All message definitions **must** include the `uint64_t timestamp` field, and this should be filled in when publishing the associated topic(s).
This field is needed in order for the logger to be able to record UORB topics.
:::
::: info
All _versioned_ messages definitions must include the `uint32 MESSAGE_VERSION` field.
For more information, refer to the [Message Versioning](#message-versioning) section.
:::
::: warning
All message definitions **must** include the `uint64_t timestamp` field, and this should be filled in when publishing the associated topic(s).
This field is needed in order for the logger to be able to record UORB topics.
:::
For example the [VelocityLimits](../msg_docs/VelocityLimits.md) message definition shown below has a descriptive comment, followed by a number of fields, which each have a comment.
```text
# Velocity and yaw rate limits for a multicopter position slow mode only
uint64 timestamp # time since system start (microseconds)
uint64 timestamp # [us] Time since system start.
# absolute speeds, NAN means use default limit
float32 horizontal_velocity # [m/s]
float32 vertical_velocity # [m/s]
float32 yaw_rate # [rad/s]
float32 horizontal_velocity # [m/s] Horizontal velocity.
float32 vertical_velocity # [m/s] Vertical velocity.
float32 yaw_rate # [rad/s] Yaw rate.
```
By default this message definition will be compiled to a single topic with an id `velocity_limits`, a direct conversion from the CamelCase name to a snake_case version.
@@ -74,16 +98,202 @@ By default this message definition will be compiled to a single topic with an id
This is the simplest form of a message.
See the existing [`msg`](../msg_docs/index.md) files for other examples of how messages are defined.
### Multi-Topic Messages
#### Message Description
Sometimes it is useful to use the same message definition for multiple topics.
This can be specified at the end of the message using a line prefixed with `# TOPICS `, followed by space-separated topic ids.
For example, the [ActuatorOutputs](../msg_docs/ActuatorOutputs.md) message definition is used to define the topic ids as shown:
Every message should start with a [comment](#comments) block that describes the message (one or more of lines that all start with `#`).
The first comment line is mandatory and provides the short description.
This may be followed by an empty comment line and then a optional long description.
```text
# TOPICS actuator_outputs actuator_outputs_sim actuator_outputs_debug
# Short description
#
# Long(er) description for the message
# that can be multiline
```
The short description should provide a succinct explanation for the purpose of the message.
Minimally it may just mirror the message name.
For example, [`BatteryStatus`](../msg_docs/BatteryStatus.md) has the short description `Battery status`.
The long description should provide any additional context required to understand what how the message is used.
It might explain who are the publishers and who are the expected consumers, such as MAVLink or the logging system.
It might also cover whether the message is only used for a particular frame type or mode.
Both short and long descriptions may be multi-line.
The long description may also include empty comment lines (the short description cannot, because the first empty comment delineates the short and long description).
A terminating full stop can be omitted from single line comments and from the final line.
The block ends at the first non-comment line, such as an empty line, field, or constant.
Any subsequent comment lines are considered "internal comments".
### Comments
Comments are text provided for explanation or documentation purposes.
Any text after a `#` character is a comment (with the exception of lines that [start with `# TOPIC`](#multi-topic-message)).
PX4 uses structured comments for message, field, and constant descriptions.
Other comments are internal.
### Fields
Messages define one or more fields, which are the variables that are written and read by publishers and subscribers, respectively.
A typical field might look like this:
```sh
float64 lat # [deg] Latitude (WGS84).
```
Each field has a _type_ followed by a _name_, and should also have a _comment_
The format is as shown:
```sh
<type> <name> # [metadata] <description>
```
- `type`:
- A primitive data type: `bool`, `char`, `uint8`, `uint32`, `uint64`, `int8`, `int16`, `int32`, `float32` and `float64`.
- Another UORB message name, when creating complex types using [nested messages](#nested-messages).
- `name`
- Any message-unique string.
By convention use lower case `underline_snake_case`.
The comment must all be on the same line as the field, and should consist of optional metadata and a description:
- `metadata` (Optional)
- Information about the field units and allowed values:
- `[<unit>]`
- The unit of measurement inside square brackets (note, no `@` delineator indicates a unit).
For example `[m]` or `[deg]`.
Typical units include: `m`, `deg`, `m/s`, `rad`, `rad/s`, and so on.
- `[@enum <enum_name>]`
- The `enum_name` gives the prefix of constant values in the message that can be assigned to the field.
Note that in UORB "enums" are a naming convention: they are not explicitly declared.
Multiple enum names indicate a possible error in the field design.
- `[@range <lower_value>, <upper_value>]`
- The allowed range of the field, specified as a `lower_value` and/or an `upper_value`.
Either value can be omitted to indicate an unbounded upper or lower value.
For example `[@range 0, 3]`, `[@range 5.3, ]`, `[@range , 3]`.
- `[@invalid <value> <description>]`
- The `value` to set the field to indicate that the field doesn't contain valid data.
The `description` is optional, and might be used to indicate the conditions under which data is invalid.
- `description`
- A concise description of the purpose of the field and allowed values, and including any important information that can't be inferred from the name!
Use a capital first letter, and omit the full stop if the description is a single sentence.
Multiple sentences may also omit the final full stop.
#### Array Fields
A array field defines multiple variables in an array, where all values have the same type.
The number of elements are given using square brackets after the type.
Array fields are otherwise defined (and documented) in the same way as other fields.
For example:
```sh
int32[12] raw_data # ADC channel raw value, accept negative value.
```
#### Mandatory Fields
All message definitions **must** include following fields:
- `uint64_t timestamp`
- This should be filled in when publishing the associated topic(s).
It is needed in order for the logger to be able to record UORB topics.
- The comment should be `# [us] Time since system start`.
### Constants
Constants specify a mapping between a name and a value.
These are mainly used to predefine useful values that you might need to use for a particular field, such as a state or flag values.
Often these are grouped together as [enums](#enums).
There are also a small number of [metadata constants](#metadata-constants) that are used by the build infrastructure.
For example, here are a number of constants for indicating battery warnings.
```sh
uint8 WARNING_NONE = 0 # No battery low voltage warning active
uint8 WARNING_LOW = 1 # Low voltage warning
```
Constants are specified as a field assigned with a value.
The field part has a _type_, which must match the type of the field they are to be used with, followed by a _name_.
They should also have a _comment_ with a description.
By convention they are defined immediately below the field with which they can used.
The format is as shown:
```sh
<type> <name> = <value> # <description>
```
- `type`:
- Must match the `type` of the field with which it is to be used.
- `name`
- The name of the constant.
This must be message-unique and is by convention `ALL_UPPER_CASE_UNDERLINE_SNAKE_CASE`
- Constant names that can be used with a field should share the same prefix and should indicate the value's purpose.
The comment must all be on the same line as the field.
Note that this is much like the field description (but there is no metadata):
- `description`
- A terse description of the purpose of the constant.
Use a capital first letter, and omit the full stop if the description is a single sentence.
Multiple sentences may also omit the final full stop.
#### Enums
Enums are groups/sets of enumerated constants that can be used as values for a particular field.
UORB does not define a formal syntax for enums.
Instead we use a prefix naming convention to indicate all the constants that are part of the same enum.
The constants in the enum should be declared immediately after the field in which they are used, and for parsing convenience, the prefix is listed in the field using `@enum` metadata.
For example, here is the definition of the `warning` field and some of the `WARNING` enum values that can be used with it:
```sh
uint8 warning # [@enum WARNING] Current battery warning
uint8 WARNING_NONE = 0 # No battery low voltage warning active
uint8 WARNING_LOW = 1 # Low voltage warning
uint8 WARNING_CRITICAL = 2 # Critical voltage, return / abort immediately
...
```
#### Metadata Constants
A number of constants provide information that is used by the PX4 build system to configure how the message may be used, such as the version and length of the message.
If relevant, these should appear near the top of the file, immediately after the [Message Description](#message-description).
The allowed constants are:
- `ORB_QUEUE_LENGTH` - Sets the [uORB Buffer Length](#uorb-buffer-length-orb-queue-length), which is used in rare cases where a subscriber needs all values that are set for a field, rather than just the most recent sample.
- `MESSAGE_VERSION` - Sets the version number of a versioned message.
This is used as part of the infrastructure to maintain compatibility between PX4 and ROS 2 versions compiled against different message definitions.
For more information see [Message Versioning](#message-versioning)
#### Multi-Topic Messages (`# TOPICS`) {#multi-topic-messages}
By default a single topic is automatically created for each message definition file, which is created by `underscore_snake_casing` the (CamelCase) message definition file name.
For example, topic `battery_status` is automatically created for the `BatteryStatus.msg`.
This is generally what you want if the message is always about the same kind of data (batteries in this case) and so all the subscribers will be interested in the same messages.
Sometimes it is useful to use the same message definition for multiple topics.
In this case the topics need to be explicitly declared.
You can do this by adding one or more lines to the end of the message prefixed with `# TOPICS`, followed by space-separated topic ids.
For example, the [VehicleGlobalPosition.msg](../msg_docs/VehicleGlobalPosition.md) message definition is used to define the topic ids as shown:
```text
# TOPICS vehicle_global_position vehicle_global_position_groundtruth external_ins_global_position
# TOPICS estimator_global_position
# TOPICS aux_global_position
```
Note that multiple topics are useful in this case because the likely subscribers for the different sources of global position are likely to be different.
### Nested Messages
Message definitions can be nested within other messages to create complex data structures.
@@ -92,15 +302,34 @@ To nest a message, simply include the nested message type in the parent message
```text
# Global position setpoint triplet in WGS84 coordinates.
#
# This are the three next waypoints (or just the next two or one).
uint64 timestamp # time since system start (microseconds)
uint64 timestamp # [us] Time since system start
PositionSetpoint previous
PositionSetpoint current
PositionSetpoint next
```
### uORB Buffer Length (ORB_QUEUE_LENGTH)
uORB messages have a single-message buffer by default, which may be overwritten if the message publication rate is too high.
In most cases this does not matter: either we are only interested in the latest sample of a topic, such as a sensor value or a setpoint, or losing a few samples is not a particular problem.
For relatively few cases, such as vehicle commands, it is important that we don't drop topics.
In order to reduce the chance that messages will be dropped we can use named constant `ORB_QUEUE_LENGTH` to create a buffer of the specified length.
For example, to create a four-message queue, add the following line to your message definition:
```sh
uint8 ORB_QUEUE_LENGTH = 4
```
As long as subscribers are able to read messages out of the buffer quickly enough than it isn't ever fully filled to the queue length (by publishers), they will be able to get all messages that are sent.
Messages will still be lost they are published when the queue is filled.
Note that the queue length value must be a power of 2 (so 2, 4, 8, ...).
### Message/Field Deprecation {#deprecation}
As there are external tools using uORB messages from log files, such as [Flight Review](https://github.com/PX4/flight_review), certain aspects need to be considered when updating existing messages:
@@ -114,7 +343,7 @@ As there are external tools using uORB messages from log files, such as [Flight
This is to ensure that removed fields (or messages) are not re-added in future.
- In case of a semantic change (e.g. the unit changes from degrees to radians), the field must be renamed as well and the previous one marked as deprecated as above.
## Message Versioning
## Message Versioning (MESSAGE_VERSION) {#message-versioning}
<Badge type="tip" text="PX4 v1.16" />
+7 -9
View File
@@ -38,7 +38,7 @@ The PX4 [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) is gen
The agent has no dependency on client code.
It can be built standalone or in a ROS 2 workspace, or installed as a snap package on Ubuntu.
When PX4 is built, a code generator uses the uORB message definitions in the source tree ([PX4-Autopilot/msg](https://github.com/PX4/PX4-Autopilot/tree/main/msg)) to compile support for the subset of uORB topics in [PX4-Autopilot/src/modules/uxrce_dds_client/dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) into [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client).
When PX4 is built, a code generator uses the uORB message definitions in the source tree ([PX4-Autopilot/msg](https://github.com/PX4/PX4-Autopilot/tree/main/msg)) to compile support for the subset of uORB topics in [/src/modules/uxrce_dds_client/dds_topics.yaml](../middleware/dds_topics.md) into [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client).
PX4 main or release builds automatically export the set of uORB messages definitions in the build to an associated branch in [PX4/px4_msgs](https://github.com/PX4/px4_msgs).
@@ -320,13 +320,11 @@ ROS_DOMAIN_ID=3 PX4_UXRCE_DDS_PORT=9999 PX4_UXRCE_DDS_NS=drone make px4_sitl gz_
## Supported uORB Messages
The set of [PX4 uORB topics](../msg_docs/index.md) that are exposed through the client are set in [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml).
The set of [PX4 uORB topics](../msg_docs/index.md) that are exposed through the client are set in [dds_topics.yaml](../middleware/dds_topics.md).
The topics are release specific (support is compiled into [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) at build time).
While most releases should support a very similar set of messages, to be certain you would need to check the yaml file for your particular release.
<!-- Jublish the set we use?: https://github.com/PX4/px4_msgs/issues/22 -->
Note that ROS 2/DDS needs to have the _same_ message definitions that were used to create the uXRCE-DDS client module in the PX4 Firmware in order to interpret the messages.
The message definitions are stored in the ROS 2 interface package [PX4/px4_msgs](https://github.com/PX4/px4_msgs), and they are automatically synchronized by CI on the `main` and release branches.
Note that all the messages from PX4 source code are present in the repository, but only those listed in `dds_topics.yaml` will be available as ROS 2 topics.
@@ -343,20 +341,20 @@ Therefore,
```
::: info
Technically, [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) completely defines the relationship between PX4 uORB topics and ROS 2 messages.
Technically, [dds_topics.yaml](../middleware/dds_topics.md) completely defines the relationship between PX4 uORB topics and ROS 2 messages.
For more information see [DDS Topics YAML](#dds-topics-yaml) below.
:::
## Customizing the Namespace
Custom topic and service namespaces can be applied at build time (changing [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml)) or at runtime (which is useful for multi vehicle operations):
Custom topic and service namespaces can be applied at build time (changing [dds_topics.yaml](../middleware/dds_topics.md)) or at runtime (which is useful for multi vehicle operations):
- One possibility is to use the `-n` option when starting the [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) from command line.
This technique can be used both in simulation and real vehicles.
- A custom namespace can be provided for simulations (only) by setting the environment variable `PX4_UXRCE_DDS_NS` before starting the simulation.
::: info
Changing the namespace at runtime will append the desired namespace as a prefix to all `topic` fields in [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) and all [service servers](#dds-ros-2-services).
Changing the namespace at runtime will append the desired namespace as a prefix to all `topic` fields in [dds_topics.yaml](../middleware/dds_topics.md) and all [service servers](#dds-ros-2-services).
Therefore, commands like:
```sh
@@ -413,7 +411,7 @@ Deadline, lifespan, and lease durations are also all set to "default".
## DDS Topics YAML
The PX4 yaml file [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) defines the set of PX4 uORB topics that are built into firmware and published.
The PX4 [dds_topics.yaml](../middleware/dds_topics.md) file defines the set of PX4 uORB topics that are built into firmware and published.
More precisely, it completely defines the relationship/pairing between PX4 uORB and ROS 2 messages.
The file is structured as follows:
@@ -542,7 +540,7 @@ Take a look at the [client startup section](#starting-the-client) to learn how t
#### New file for setting which topics are published
The list of topics that are published and subscribed for a particular firmware is now managed by the [dds_topic.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) configuration file, which replaces [urtps_bridge_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/release/1.13/msg/tools/urtps_bridge_topics.yaml)
The list of topics that are published and subscribed for a particular firmware is now managed by the [dds_topics.yaml](../middleware/dds_topics.md) configuration file, which replaces [urtps_bridge_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/release/1.13/msg/tools/urtps_bridge_topics.yaml)
See [Supported uORB Messages](#supported-uorb-messages) and [DDS Topics YAML](#dds-topics-yaml) sections for more information.
+3 -3
View File
@@ -28,7 +28,7 @@ The agent acts as a proxy for the client to publish and subscribe to topics in t
The PX4 [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) is generated at build time and included in PX4 firmware by default.
It includes both the "generic" micro XRCE-DDS client code, and PX4-specific translation code that it uses to publish to/from uORB topics.
The subset of uORB messages that are generated into the client are listed in [PX4-Autopilot/src/modules/uxrce_dds_client/dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml).
The subset of uORB messages that are generated into the client are specified in [dds_topics.yaml](../middleware/dds_topics.md).
The generator uses the uORB message definitions in the source tree: [PX4-Autopilot/msg](https://github.com/PX4/PX4-Autopilot/tree/main/msg) to create the code for sending ROS 2 messages.
ROS 2 applications need to be built in a workspace that has the _same_ message definitions that were used to create the uXRCE-DDS client module in the PX4 Firmware.
@@ -394,7 +394,7 @@ To control applications, ROS 2 applications:
- subscribe to (listen to) telemetry topics published by PX4
- publish to topics that cause PX4 to perform some action.
The topics that you can use are defined in [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), and you can get more information about their data in the [uORB Message Reference](../msg_docs/index.md).
The topics that you can use are defined in [dds_topics.yaml](../middleware/dds_topics.md), and you can get more information about their data in the [uORB Message Reference](../msg_docs/index.md).
For example, [VehicleGlobalPosition](../msg_docs/VehicleGlobalPosition.md) can be used to get the vehicle global position, while [VehicleCommand](../msg_docs/VehicleCommand.md) can be used to command actions such as takeoff and land.
The [ROS 2 Example applications](#ros-2-example-applications) examples below provide concrete examples of how to use these topics.
@@ -728,7 +728,7 @@ Custom topic and service namespaces can be applied at build time (changing [dds_
- A custom namespace can be provided for simulations (only) by setting the environment variable `PX4_UXRCE_DDS_NS` before starting the simulation.
::: info
Changing the namespace at runtime will append the desired namespace as a prefix to all `topic` fields in [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) and all [service servers](#px4-ros-2-service-servers).
Changing the namespace at runtime will append the desired namespace as a prefix to all `topic` fields in [dds_topics.yaml](../middleware/dds_topics.md) and all [service servers](#px4-ros-2-service-servers).
Therefore, commands like:
```sh
+19 -8
View File
@@ -460,6 +460,7 @@
- [Vehicles](/sim_gazebo_gz/vehicles.md)
- [Advanced Lift Drag Tool](/sim_gazebo_gz/tools_avl_automation.md)
- [Worlds](/sim_gazebo_gz/worlds.md)
- [Plugins](/sim_gazebo_gz/plugins.md)
- [Gazebo Models Repository](/sim_gazebo_gz/gazebo_models.md)
- [Multi-Vehicle Sim](/sim_gazebo_gz/multi_vehicle_simulation.md)
- [Gazebo Classic Simulation](/sim_gazebo_classic/index.md)
@@ -492,12 +493,17 @@
- [Versioned](/msg_docs/versioned_messages.md)
- [ActuatorMotors](/msg_docs/ActuatorMotors.md)
- [ActuatorServos](/msg_docs/ActuatorServos.md)
- [AirspeedValidated](/msg_docs/AirspeedValidated.md)
- [ArmingCheckReply](/msg_docs/ArmingCheckReply.md)
- [ArmingCheckRequest](/msg_docs/ArmingCheckRequest.md)
- [BatteryStatus](/msg_docs/BatteryStatus.md)
- [ConfigOverrides](/msg_docs/ConfigOverrides.md)
- [FixedWingLateralSetpoint](/msg_docs/FixedWingLateralSetpoint.md)
- [FixedWingLongitudinalSetpoint](/msg_docs/FixedWingLongitudinalSetpoint.md)
- [GotoSetpoint](/msg_docs/GotoSetpoint.md)
- [HomePosition](/msg_docs/HomePosition.md)
- [LateralControlConfiguration](/msg_docs/LateralControlConfiguration.md)
- [LongitudinalControlConfiguration](/msg_docs/LongitudinalControlConfiguration.md)
- [ManualControlSetpoint](/msg_docs/ManualControlSetpoint.md)
- [ModeCompleted](/msg_docs/ModeCompleted.md)
- [RegisterExtComponentReply](/msg_docs/RegisterExtComponentReply.md)
@@ -526,10 +532,8 @@
- [ActuatorTest](/msg_docs/ActuatorTest.md)
- [AdcReport](/msg_docs/AdcReport.md)
- [Airspeed](/msg_docs/Airspeed.md)
- [AirspeedValidated](/msg_docs/AirspeedValidated.md)
- [AirspeedWind](/msg_docs/AirspeedWind.md)
- [AutotuneAttitudeControlStatus](/msg_docs/AutotuneAttitudeControlStatus.md)
- [Buffer128](/msg_docs/Buffer128.md)
- [ButtonEvent](/msg_docs/ButtonEvent.md)
- [CameraCapture](/msg_docs/CameraCapture.md)
- [CameraStatus](/msg_docs/CameraStatus.md)
@@ -568,6 +572,9 @@
- [FailsafeFlags](/msg_docs/FailsafeFlags.md)
- [FailureDetectorStatus](/msg_docs/FailureDetectorStatus.md)
- [FigureEightStatus](/msg_docs/FigureEightStatus.md)
- [FixedWingLateralGuidanceStatus](/msg_docs/FixedWingLateralGuidanceStatus.md)
- [FixedWingLateralStatus](/msg_docs/FixedWingLateralStatus.md)
- [FixedWingRunwayControl](/msg_docs/FixedWingRunwayControl.md)
- [FlightPhaseEstimation](/msg_docs/FlightPhaseEstimation.md)
- [FollowTarget](/msg_docs/FollowTarget.md)
- [FollowTargetEstimator](/msg_docs/FollowTargetEstimator.md)
@@ -620,7 +627,6 @@
- [NavigatorMissionItem](/msg_docs/NavigatorMissionItem.md)
- [NavigatorStatus](/msg_docs/NavigatorStatus.md)
- [NormalizedUnsignedSetpoint](/msg_docs/NormalizedUnsignedSetpoint.md)
- [NpfgStatus](/msg_docs/NpfgStatus.md)
- [ObstacleDistance](/msg_docs/ObstacleDistance.md)
- [OffboardControlMode](/msg_docs/OffboardControlMode.md)
- [OnboardComputerStatus](/msg_docs/OnboardComputerStatus.md)
@@ -656,13 +662,12 @@
- [RcParameterMap](/msg_docs/RcParameterMap.md)
- [RoverAttitudeSetpoint](/msg_docs/RoverAttitudeSetpoint.md)
- [RoverAttitudeStatus](/msg_docs/RoverAttitudeStatus.md)
- [RoverMecanumGuidanceStatus](/msg_docs/RoverMecanumGuidanceStatus.md)
- [RoverMecanumSetpoint](/msg_docs/RoverMecanumSetpoint.md)
- [RoverMecanumStatus](/msg_docs/RoverMecanumStatus.md)
- [RoverPositionSetpoint](/msg_docs/RoverPositionSetpoint.md)
- [RoverRateSetpoint](/msg_docs/RoverRateSetpoint.md)
- [RoverRateStatus](/msg_docs/RoverRateStatus.md)
- [RoverSteeringSetpoint](/msg_docs/RoverSteeringSetpoint.md)
- [RoverThrottleSetpoint](/msg_docs/RoverThrottleSetpoint.md)
- [RoverVelocitySetpoint](/msg_docs/RoverVelocitySetpoint.md)
- [RoverVelocityStatus](/msg_docs/RoverVelocityStatus.md)
- [Rpm](/msg_docs/Rpm.md)
- [RtlStatus](/msg_docs/RtlStatus.md)
@@ -694,6 +699,7 @@
- [TelemetryStatus](/msg_docs/TelemetryStatus.md)
- [TiltrotorExtraControls](/msg_docs/TiltrotorExtraControls.md)
- [TimesyncStatus](/msg_docs/TimesyncStatus.md)
- [TrajectorySetpoint6dof](/msg_docs/TrajectorySetpoint6dof.md)
- [TransponderReport](/msg_docs/TransponderReport.md)
- [TuneControl](/msg_docs/TuneControl.md)
- [UavcanParameterRequest](/msg_docs/UavcanParameterRequest.md)
@@ -717,13 +723,16 @@
- [WheelEncoders](/msg_docs/WheelEncoders.md)
- [Wind](/msg_docs/Wind.md)
- [YawEstimatorStatus](/msg_docs/YawEstimatorStatus.md)
- [AirspeedValidatedV0](/msg_docs/AirspeedValidatedV0.md)
- [VehicleAttitudeSetpointV0](/msg_docs/VehicleAttitudeSetpointV0.md)
- [VehicleStatusV0](/msg_docs/VehicleStatusV0.md)
- [MAVLink Messaging](/middleware/mavlink.md)
- [MAVLink Messaging](/mavlink/index.md)
- [Adding Messages](/mavlink/adding_messages.md)
- [Streaming Messages](/mavlink/streaming_messages.md)
- [Receiving Messages](/mavlink/receiving_messages.md)
- [Custom MAVLink Messages](/mavlink/custom_messages.md)
- [Standard Modes Protocol](/mavlink/standard_modes.md)
- [Protocols/Microservices](/mavlink/protocols.md)
- [Standard Modes Protocol](/mavlink/standard_modes.md)
- [uXRCE-DDS (PX4-ROS 2/DDS Bridge)](/middleware/uxrce_dds.md)
- [모듈과 명령어](/modules/modules_main.md)
- [자동 튜닝](/modules/modules_autotune.md)
@@ -740,6 +749,7 @@
- [자기 센서](/modules/modules_driver_magnetometer.md)
- [광류 센서](/modules/modules_driver_optical_flow.md)
- [Rpm Sensor](/modules/modules_driver_rpm_sensor.md)
- [Radio Control](/modules/modules_driver_radio_control.md)
- [Transponder](/modules/modules_driver_transponder.md)
- [추정기](/modules/modules_estimator.md)
- [시뮬레이션](/modules/modules_simulation.md)
@@ -852,6 +862,7 @@
- [출시](/releases/index.md)
- [main (alpha)](/releases/main.md)
- [1.16 (release candidate)](/releases/1.16.md)
- [1.15 (stable)](/releases/1.15.md)
- [1.14](/releases/1.14.md)
- [1.13](/releases/1.13.md)
+58 -58
View File
@@ -47,7 +47,7 @@ PX4 v1.14 (and later) supports the [LightWare LiDAR SF45](../sensor/sf45_rotatin
- Attach and configure the distance sensor on a particular port (see [sensor-specific docs](../sensor/rangefinders.md)) and enable collision prevention using [CP_DIST](#CP_DIST).
- 방향을 설정하려면 드라이버를 수정하십시오.
This should be done by mimicking the `SENS_CM8JL65_R_0` parameter (though you might also hard-code the orientation in the sensor _module.yaml_ file to something like `sf0x start -d ${SERIAL_DEV} -R 25` - where 25 is equivalent to `ROTATION_DOWNWARD_FACING`).
This should be done by mimicking the `SENS_CM8JL65_R_0` parameter (though you might also hard-code the orientation in the sensor _module.yaml_ file to something like `sf0x start -d ${SERIAL_DEV} -R 25` - where 25 is equivalent to `ROTATION_DOWNWARD_FACING`).
- Modify the driver to set the _field of view_ in the distance sensor UORB topic (`distance_sensor_s.h_fov`).
## PX4 (Software) Setup
@@ -203,85 +203,85 @@ The Lua script works by extracting the `obstacle_distance_fused` data at each ti
2. Configure PX4 to publish obstacle distance data (so that it is available to PlotJuggler):
Add the [`obstacle_distance_fused`](../msg_docs/ObstacleDistance.md) UORB topic to your [`dds_topics.yaml`](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) so that it is published by PX4:
Add the [`obstacle_distance_fused`](../msg_docs/ObstacleDistance.md) UORB topic to your [`dds_topics.yaml`](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) so that it is published by PX4:
```sh
- topic: /fmu/out/obstacle_distance_fused
type: px4_msgs::msg::ObstacleDistance
```
```sh
- topic: /fmu/out/obstacle_distance_fused
type: px4_msgs::msg::ObstacleDistance
```
For more information see [DDS Topics YAML](../middleware/uxrce_dds.md#dds-topics-yaml) in _uXRCE-DDS (PX4-ROS 2/DDS Bridge)_.
For more information see [DDS Topics YAML](../middleware/uxrce_dds.md#dds-topics-yaml) in [uXRCE-DDS](../middleware/uxrce_dds.md) (PX4-ROS 2/DDS Bridge)_.
3. Open PlotJuggler and navigate to the **Tools > Reactive Script Editor** section.
In the **Script Editor** tab, add following scripts in the appropriate sections:
In the **Script Editor** tab, add following scripts in the appropriate sections:
- **Global code, executed once:**
- **Global code, executed once:**
```lua
obs_dist_fused_xy = ScatterXY.new("obstacle_distance_fused_xy")
obs_dist_min = Timeseries.new("obstacle_distance_minimum")
```
```lua
obs_dist_fused_xy = ScatterXY.new("obstacle_distance_fused_xy")
obs_dist_min = Timeseries.new("obstacle_distance_minimum")
```
- **function(tracker_time)**
- **function(tracker_time)**
```lua
obs_dist_fused_xy:clear()
```lua
obs_dist_fused_xy:clear()
i = 0
angle_offset = TimeseriesView.find("/fmu/out/obstacle_distance_fused/angle_offset")
increment = TimeseriesView.find("/fmu/out/obstacle_distance_fused/increment")
min_dist = 65535
i = 0
angle_offset = TimeseriesView.find("/fmu/out/obstacle_distance_fused/angle_offset")
increment = TimeseriesView.find("/fmu/out/obstacle_distance_fused/increment")
min_dist = 65535
-- Cache increment and angle_offset values at tracker_time to avoid repeated calls
local angle_offset_value = angle_offset:atTime(tracker_time)
local increment_value = increment:atTime(tracker_time)
-- Cache increment and angle_offset values at tracker_time to avoid repeated calls
local angle_offset_value = angle_offset:atTime(tracker_time)
local increment_value = increment:atTime(tracker_time)
if increment_value == nil or increment_value <= 0 then
print("Invalid increment value: " .. tostring(increment_value))
return
end
if increment_value == nil or increment_value <= 0 then
print("Invalid increment value: " .. tostring(increment_value))
return
end
local max_steps = math.floor(360 / increment_value)
local max_steps = math.floor(360 / increment_value)
while i < max_steps do
local str = string.format("/fmu/out/obstacle_distance_fused/distances[%d]", i)
local distance = TimeseriesView.find(str)
if distance == nil then
print("No distance data for: " .. str)
break
end
while i < max_steps do
local str = string.format("/fmu/out/obstacle_distance_fused/distances[%d]", i)
local distance = TimeseriesView.find(str)
if distance == nil then
print("No distance data for: " .. str)
break
end
local dist = distance:atTime(tracker_time)
if dist ~= nil and dist < 65535 then
-- Calculate angle and Cartesian coordinates
local angle = angle_offset_value + i * increment_value
local y = dist * math.cos(math.rad(angle))
local x = dist * math.sin(math.rad(angle))
local dist = distance:atTime(tracker_time)
if dist ~= nil and dist < 65535 then
-- Calculate angle and Cartesian coordinates
local angle = angle_offset_value + i * increment_value
local y = dist * math.cos(math.rad(angle))
local x = dist * math.sin(math.rad(angle))
obs_dist_fused_xy:push_back(x, y)
obs_dist_fused_xy:push_back(x, y)
-- Update minimum distance
if dist < min_dist then
min_dist = dist
end
end
-- Update minimum distance
if dist < min_dist then
min_dist = dist
end
end
i = i + 1
end
i = i + 1
end
-- Push minimum distance once after the loop
if min_dist < 65535 then
obs_dist_min:push_back(tracker_time, min_dist)
else
print("No valid minimum distance found")
end
```
-- Push minimum distance once after the loop
if min_dist < 65535 then
obs_dist_min:push_back(tracker_time, min_dist)
else
print("No valid minimum distance found")
end
```
4. Enter a name for the script on the top right, and press **Save**.
Once saved, the script should appear in the _Active Scripts_ section.
Once saved, the script should appear in the _Active Scripts_ section.
5. Start streaming the data using the approach described in [Plotting uORB Topic Data in Real Time using PlotJuggler](../debug/plotting_realtime_uorb_data.md).
You should see the `obstacle_distance_fused_xy` and `obstacle_distance_minimum` timeseries on the left.
You should see the `obstacle_distance_fused_xy` and `obstacle_distance_minimum` timeseries on the left.
Note that you have to press **Save** again to re-enable the scripts after loading a new log file or otherwise clearing data.
+3 -3
View File
@@ -96,13 +96,13 @@ Exporting the messages allows ROS 2 and the uXRCE-DDS agent to be independent of
While `px4_msgs` has messages for all uORB topics in PX4, not all messages in `px4_msgs` are available to ROS 2/PlotJuggler by default.
The set that are available must be built into the client running on PX4.
These are defined in [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml).
These are defined in [dds_topics.yaml](../middleware/dds_topics.md).
The instructions below explain the changes needed to monitor topics that are not available by default.
### Missing Topics
If a normal uORB topic is not available in PlotJuggler you will need to modify the [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) to include the topic and rebuild PX4.
If a normal uORB topic is not available in PlotJuggler you will need to modify the [dds_topics.yaml](../middleware/dds_topics.md) ([source](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml)) to include the topic and rebuild PX4.
If working with real hardware you will need to build and [install](../config/firmware.md#installing-px4-main-beta-or-custom-firmware) custom firmware after changing the YAML file.
@@ -122,7 +122,7 @@ cd ~/ros2_ws/ && colcon build
### Custom Topics
After defining the topic, follow the instructions above to add the topic to [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), and export the new message into your ROS 2 workspace.
After defining the topic, follow the instructions above to add the topic to [dds_topics.yaml](../middleware/dds_topics.md), and export the new message into your ROS 2 workspace.
## See also
+1 -2
View File
@@ -128,8 +128,7 @@ In EKF2 mode, the replay will automatically create the ORB publisher rules descr
To perform an EKF2 replay:
- Record the original log.
Optionally set `SDLOG_MODE` to `1` to log from boot.
- Record the original log with `SDLOG_MODE` set to `1` to log from boot.
- In addition to the `replay` environment variable, set `replay_mode` to `ekf2`:
+24 -5
View File
@@ -61,12 +61,12 @@ For example the [VelocityLimits](../msg_docs/VelocityLimits.md) message definiti
```text
# Velocity and yaw rate limits for a multicopter position slow mode only
uint64 timestamp # time since system start (microseconds)
uint64 timestamp # [us] Time since system start.
# absolute speeds, NAN means use default limit
float32 horizontal_velocity # [m/s]
float32 vertical_velocity # [m/s]
float32 yaw_rate # [rad/s]
float32 horizontal_velocity # [m/s] Horizontal velocity.
float32 vertical_velocity # [m/s] Vertical velocity.
float32 yaw_rate # [rad/s] Yaw rate.
```
By default this message definition will be compiled to a single topic with an id `velocity_limits`, a direct conversion from the CamelCase name to a snake_case version.
@@ -92,15 +92,34 @@ To nest a message, simply include the nested message type in the parent message
```text
# Global position setpoint triplet in WGS84 coordinates.
#
# This are the three next waypoints (or just the next two or one).
uint64 timestamp # time since system start (microseconds)
uint64 timestamp # [us] Time since system start.
PositionSetpoint previous
PositionSetpoint current
PositionSetpoint next
```
### uORB Buffer Length (ORB_QUEUE_LENGTH)
uORB messages have a single-message buffer by default, which may be overwritten if the message publication rate is too high.
In most cases this does not matter: either we are only interested in the latest sample of a topic, such as a sensor value or a setpoint, or losing a few samples is not a particular problem.
For relatively few cases, such as vehicle commands, it is important that we don't drop topics.
In order to reduce the chance that messages will be dropped we can use named constant `ORB_QUEUE_LENGTH` to create a buffer of the specified length.
For example, to create a four-message queue, add the following line to your message definition:
```sh
uint8 ORB_QUEUE_LENGTH = 4
```
As long as subscribers are able to read messages out of the buffer quickly enough than it isn't ever fully filled to the queue length (by publishers), they will be able to get all messages that are sent.
Messages will still be lost they are published when the queue is filled.
Note that the queue length value must be a power of 2 (so 2, 4, 8, ...).
### Message/Field Deprecation {#deprecation}
As there are external tools using uORB messages from log files, such as [Flight Review](https://github.com/PX4/flight_review), certain aspects need to be considered when updating existing messages:
+19 -8
View File
@@ -460,6 +460,7 @@
- [Vehicles](/sim_gazebo_gz/vehicles.md)
- [Advanced Lift Drag Tool](/sim_gazebo_gz/tools_avl_automation.md)
- [Worlds](/sim_gazebo_gz/worlds.md)
- [Plugins](/sim_gazebo_gz/plugins.md)
- [Gazebo Models Repository](/sim_gazebo_gz/gazebo_models.md)
- [Багатотранспортний Sim](/sim_gazebo_gz/multi_vehicle_simulation.md)
- [Симуляція Gazebo Classic](/sim_gazebo_classic/index.md)
@@ -492,12 +493,17 @@
- [Versioned](/msg_docs/versioned_messages.md)
- [ActuatorMotors](/msg_docs/ActuatorMotors.md)
- [ActuatorServos](/msg_docs/ActuatorServos.md)
- [AirspeedValidated](/msg_docs/AirspeedValidated.md)
- [ArmingCheckReply](/msg_docs/ArmingCheckReply.md)
- [ArmingCheckRequest](/msg_docs/ArmingCheckRequest.md)
- [BatteryStatus](/msg_docs/BatteryStatus.md)
- [ConfigOverrides](/msg_docs/ConfigOverrides.md)
- [FixedWingLateralSetpoint](/msg_docs/FixedWingLateralSetpoint.md)
- [FixedWingLongitudinalSetpoint](/msg_docs/FixedWingLongitudinalSetpoint.md)
- [GotoSetpoint](/msg_docs/GotoSetpoint.md)
- [HomePosition](/msg_docs/HomePosition.md)
- [LateralControlConfiguration](/msg_docs/LateralControlConfiguration.md)
- [LongitudinalControlConfiguration](/msg_docs/LongitudinalControlConfiguration.md)
- [ManualControlSetpoint](/msg_docs/ManualControlSetpoint.md)
- [ModeCompleted](/msg_docs/ModeCompleted.md)
- [RegisterExtComponentReply](/msg_docs/RegisterExtComponentReply.md)
@@ -526,10 +532,8 @@
- [ActuatorTest](/msg_docs/ActuatorTest.md)
- [AdcReport](/msg_docs/AdcReport.md)
- [Airspeed](/msg_docs/Airspeed.md)
- [AirspeedValidated](/msg_docs/AirspeedValidated.md)
- [AirspeedWind](/msg_docs/AirspeedWind.md)
- [AutotuneAttitudeControlStatus](/msg_docs/AutotuneAttitudeControlStatus.md)
- [Buffer128](/msg_docs/Buffer128.md)
- [ButtonEvent](/msg_docs/ButtonEvent.md)
- [CameraCapture](/msg_docs/CameraCapture.md)
- [CameraStatus](/msg_docs/CameraStatus.md)
@@ -568,6 +572,9 @@
- [FailsafeFlags](/msg_docs/FailsafeFlags.md)
- [FailureDetectorStatus](/msg_docs/FailureDetectorStatus.md)
- [FigureEightStatus](/msg_docs/FigureEightStatus.md)
- [FixedWingLateralGuidanceStatus](/msg_docs/FixedWingLateralGuidanceStatus.md)
- [FixedWingLateralStatus](/msg_docs/FixedWingLateralStatus.md)
- [FixedWingRunwayControl](/msg_docs/FixedWingRunwayControl.md)
- [FlightPhaseEstimation](/msg_docs/FlightPhaseEstimation.md)
- [FollowTarget](/msg_docs/FollowTarget.md)
- [FollowTargetEstimator](/msg_docs/FollowTargetEstimator.md)
@@ -620,7 +627,6 @@
- [NavigatorMissionItem](/msg_docs/NavigatorMissionItem.md)
- [NavigatorStatus](/msg_docs/NavigatorStatus.md)
- [NormalizedUnsignedSetpoint](/msg_docs/NormalizedUnsignedSetpoint.md)
- [NpfgStatus](/msg_docs/NpfgStatus.md)
- [ObstacleDistance](/msg_docs/ObstacleDistance.md)
- [OffboardControlMode](/msg_docs/OffboardControlMode.md)
- [OnboardComputerStatus](/msg_docs/OnboardComputerStatus.md)
@@ -656,13 +662,12 @@
- [RcParameterMap](/msg_docs/RcParameterMap.md)
- [RoverAttitudeSetpoint](/msg_docs/RoverAttitudeSetpoint.md)
- [RoverAttitudeStatus](/msg_docs/RoverAttitudeStatus.md)
- [RoverMecanumGuidanceStatus](/msg_docs/RoverMecanumGuidanceStatus.md)
- [RoverMecanumSetpoint](/msg_docs/RoverMecanumSetpoint.md)
- [RoverMecanumStatus](/msg_docs/RoverMecanumStatus.md)
- [RoverPositionSetpoint](/msg_docs/RoverPositionSetpoint.md)
- [RoverRateSetpoint](/msg_docs/RoverRateSetpoint.md)
- [RoverRateStatus](/msg_docs/RoverRateStatus.md)
- [RoverSteeringSetpoint](/msg_docs/RoverSteeringSetpoint.md)
- [RoverThrottleSetpoint](/msg_docs/RoverThrottleSetpoint.md)
- [RoverVelocitySetpoint](/msg_docs/RoverVelocitySetpoint.md)
- [RoverVelocityStatus](/msg_docs/RoverVelocityStatus.md)
- [Rpm](/msg_docs/Rpm.md)
- [RtlStatus](/msg_docs/RtlStatus.md)
@@ -694,6 +699,7 @@
- [TelemetryStatus](/msg_docs/TelemetryStatus.md)
- [TiltrotorExtraControls](/msg_docs/TiltrotorExtraControls.md)
- [TimesyncStatus](/msg_docs/TimesyncStatus.md)
- [TrajectorySetpoint6dof](/msg_docs/TrajectorySetpoint6dof.md)
- [TransponderReport](/msg_docs/TransponderReport.md)
- [TuneControl](/msg_docs/TuneControl.md)
- [UavcanParameterRequest](/msg_docs/UavcanParameterRequest.md)
@@ -717,13 +723,16 @@
- [WheelEncoders](/msg_docs/WheelEncoders.md)
- [Wind](/msg_docs/Wind.md)
- [YawEstimatorStatus](/msg_docs/YawEstimatorStatus.md)
- [AirspeedValidatedV0](/msg_docs/AirspeedValidatedV0.md)
- [VehicleAttitudeSetpointV0](/msg_docs/VehicleAttitudeSetpointV0.md)
- [VehicleStatusV0](/msg_docs/VehicleStatusV0.md)
- [Повідомлення MAVLink](/middleware/mavlink.md)
- [MAVLink Messaging](/mavlink/index.md)
- [Adding Messages](/mavlink/adding_messages.md)
- [Streaming Messages](/mavlink/streaming_messages.md)
- [Receiving Messages](/mavlink/receiving_messages.md)
- [Custom MAVLink Messages](/mavlink/custom_messages.md)
- [Standard Modes Protocol](/mavlink/standard_modes.md)
- [Protocols/Microservices](/mavlink/protocols.md)
- [Standard Modes Protocol](/mavlink/standard_modes.md)
- [uXRCE-DDS (PX4-ROS 2/DDS Bridge)](/middleware/uxrce_dds.md)
- [Модулі & Команди](/modules/modules_main.md)
- [Автоматичне підлаштування](/modules/modules_autotune.md)
@@ -740,6 +749,7 @@
- [Магнітометр](/modules/modules_driver_magnetometer.md)
- [Оптичний потік](/modules/modules_driver_optical_flow.md)
- [Датчик швидкості обертання](/modules/modules_driver_rpm_sensor.md)
- [Radio Control](/modules/modules_driver_radio_control.md)
- [Транспондер](/modules/modules_driver_transponder.md)
- [Естіматори](/modules/modules_estimator.md)
- [Симуляції](/modules/modules_simulation.md)
@@ -852,6 +862,7 @@
- [Релізи](/releases/index.md)
- [main (alpha)](/releases/main.md)
- [1.16 (release candidate)](/releases/1.16.md)
- [1.15 (stable)](/releases/1.15.md)
- [1.14](/releases/1.14.md)
- [1.13](/releases/1.13.md)
+58 -58
View File
@@ -47,7 +47,7 @@ PX4 v1.14 (and later) supports the [LightWare LiDAR SF45](../sensor/sf45_rotatin
- Attach and configure the distance sensor on a particular port (see [sensor-specific docs](../sensor/rangefinders.md)) and enable collision prevention using [CP_DIST](#CP_DIST).
- Модифікуйте драйвер для встановлення орієнтації.
This should be done by mimicking the `SENS_CM8JL65_R_0` parameter (though you might also hard-code the orientation in the sensor _module.yaml_ file to something like `sf0x start -d ${SERIAL_DEV} -R 25` - where 25 is equivalent to `ROTATION_DOWNWARD_FACING`).
This should be done by mimicking the `SENS_CM8JL65_R_0` parameter (though you might also hard-code the orientation in the sensor _module.yaml_ file to something like `sf0x start -d ${SERIAL_DEV} -R 25` - where 25 is equivalent to `ROTATION_DOWNWARD_FACING`).
- Modify the driver to set the _field of view_ in the distance sensor UORB topic (`distance_sensor_s.h_fov`).
## PX4 (Software) Setup
@@ -203,85 +203,85 @@ The Lua script works by extracting the `obstacle_distance_fused` data at each ti
2. Configure PX4 to publish obstacle distance data (so that it is available to PlotJuggler):
Add the [`obstacle_distance_fused`](../msg_docs/ObstacleDistance.md) UORB topic to your [`dds_topics.yaml`](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) so that it is published by PX4:
Add the [`obstacle_distance_fused`](../msg_docs/ObstacleDistance.md) UORB topic to your [`dds_topics.yaml`](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) so that it is published by PX4:
```sh
- topic: /fmu/out/obstacle_distance_fused
type: px4_msgs::msg::ObstacleDistance
```
```sh
- topic: /fmu/out/obstacle_distance_fused
type: px4_msgs::msg::ObstacleDistance
```
For more information see [DDS Topics YAML](../middleware/uxrce_dds.md#dds-topics-yaml) in _uXRCE-DDS (PX4-ROS 2/DDS Bridge)_.
For more information see [DDS Topics YAML](../middleware/uxrce_dds.md#dds-topics-yaml) in [uXRCE-DDS](../middleware/uxrce_dds.md) (PX4-ROS 2/DDS Bridge)_.
3. Open PlotJuggler and navigate to the **Tools > Reactive Script Editor** section.
In the **Script Editor** tab, add following scripts in the appropriate sections:
In the **Script Editor** tab, add following scripts in the appropriate sections:
- **Global code, executed once:**
- **Global code, executed once:**
```lua
obs_dist_fused_xy = ScatterXY.new("obstacle_distance_fused_xy")
obs_dist_min = Timeseries.new("obstacle_distance_minimum")
```
```lua
obs_dist_fused_xy = ScatterXY.new("obstacle_distance_fused_xy")
obs_dist_min = Timeseries.new("obstacle_distance_minimum")
```
- **function(tracker_time)**
- **function(tracker_time)**
```lua
obs_dist_fused_xy:clear()
```lua
obs_dist_fused_xy:clear()
i = 0
angle_offset = TimeseriesView.find("/fmu/out/obstacle_distance_fused/angle_offset")
increment = TimeseriesView.find("/fmu/out/obstacle_distance_fused/increment")
min_dist = 65535
i = 0
angle_offset = TimeseriesView.find("/fmu/out/obstacle_distance_fused/angle_offset")
increment = TimeseriesView.find("/fmu/out/obstacle_distance_fused/increment")
min_dist = 65535
-- Cache increment and angle_offset values at tracker_time to avoid repeated calls
local angle_offset_value = angle_offset:atTime(tracker_time)
local increment_value = increment:atTime(tracker_time)
-- Cache increment and angle_offset values at tracker_time to avoid repeated calls
local angle_offset_value = angle_offset:atTime(tracker_time)
local increment_value = increment:atTime(tracker_time)
if increment_value == nil or increment_value <= 0 then
print("Invalid increment value: " .. tostring(increment_value))
return
end
if increment_value == nil or increment_value <= 0 then
print("Invalid increment value: " .. tostring(increment_value))
return
end
local max_steps = math.floor(360 / increment_value)
local max_steps = math.floor(360 / increment_value)
while i < max_steps do
local str = string.format("/fmu/out/obstacle_distance_fused/distances[%d]", i)
local distance = TimeseriesView.find(str)
if distance == nil then
print("No distance data for: " .. str)
break
end
while i < max_steps do
local str = string.format("/fmu/out/obstacle_distance_fused/distances[%d]", i)
local distance = TimeseriesView.find(str)
if distance == nil then
print("No distance data for: " .. str)
break
end
local dist = distance:atTime(tracker_time)
if dist ~= nil and dist < 65535 then
-- Calculate angle and Cartesian coordinates
local angle = angle_offset_value + i * increment_value
local y = dist * math.cos(math.rad(angle))
local x = dist * math.sin(math.rad(angle))
local dist = distance:atTime(tracker_time)
if dist ~= nil and dist < 65535 then
-- Calculate angle and Cartesian coordinates
local angle = angle_offset_value + i * increment_value
local y = dist * math.cos(math.rad(angle))
local x = dist * math.sin(math.rad(angle))
obs_dist_fused_xy:push_back(x, y)
obs_dist_fused_xy:push_back(x, y)
-- Update minimum distance
if dist < min_dist then
min_dist = dist
end
end
-- Update minimum distance
if dist < min_dist then
min_dist = dist
end
end
i = i + 1
end
i = i + 1
end
-- Push minimum distance once after the loop
if min_dist < 65535 then
obs_dist_min:push_back(tracker_time, min_dist)
else
print("No valid minimum distance found")
end
```
-- Push minimum distance once after the loop
if min_dist < 65535 then
obs_dist_min:push_back(tracker_time, min_dist)
else
print("No valid minimum distance found")
end
```
4. Enter a name for the script on the top right, and press **Save**.
Once saved, the script should appear in the _Active Scripts_ section.
Once saved, the script should appear in the _Active Scripts_ section.
5. Start streaming the data using the approach described in [Plotting uORB Topic Data in Real Time using PlotJuggler](../debug/plotting_realtime_uorb_data.md).
You should see the `obstacle_distance_fused_xy` and `obstacle_distance_minimum` timeseries on the left.
You should see the `obstacle_distance_fused_xy` and `obstacle_distance_minimum` timeseries on the left.
Note that you have to press **Save** again to re-enable the scripts after loading a new log file or otherwise clearing data.
+3 -3
View File
@@ -96,13 +96,13 @@ Exporting the messages allows ROS 2 and the uXRCE-DDS agent to be independent of
While `px4_msgs` has messages for all uORB topics in PX4, not all messages in `px4_msgs` are available to ROS 2/PlotJuggler by default.
The set that are available must be built into the client running on PX4.
These are defined in [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml).
These are defined in [dds_topics.yaml](../middleware/dds_topics.md).
The instructions below explain the changes needed to monitor topics that are not available by default.
### Missing Topics
If a normal uORB topic is not available in PlotJuggler you will need to modify the [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) to include the topic and rebuild PX4.
If a normal uORB topic is not available in PlotJuggler you will need to modify the [dds_topics.yaml](../middleware/dds_topics.md) ([source](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml)) to include the topic and rebuild PX4.
If working with real hardware you will need to build and [install](../config/firmware.md#installing-px4-main-beta-or-custom-firmware) custom firmware after changing the YAML file.
@@ -122,7 +122,7 @@ cd ~/ros2_ws/ && colcon build
### Custom Topics
After defining the topic, follow the instructions above to add the topic to [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), and export the new message into your ROS 2 workspace.
After defining the topic, follow the instructions above to add the topic to [dds_topics.yaml](../middleware/dds_topics.md), and export the new message into your ROS 2 workspace.
## Дивись також
+1 -2
View File
@@ -128,8 +128,7 @@ To enable recording for EKF replay you must set the parameters to enable a [sing
Для виконання повторення EKF2:
- Запишіть оригінальний журнал.
Optionally set `SDLOG_MODE` to `1` to log from boot.
- Record the original log with `SDLOG_MODE` set to `1` to log from boot.
- In addition to the `replay` environment variable, set `replay_mode` to `ekf2`:
+277
View File
@@ -0,0 +1,277 @@
# dds_topics.yaml — PX4 Topics Exposed to ROS 2
:::info
This document is [auto-generated](https://github.com/PX4/PX4-Autopilot/blob/main/Tools/msg/generate_msg_docs.py) from the source code.
:::
The [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) file specifies which uORB message definitions are compiled into the [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) module when [PX4 is built](../middleware/uxrce_dds.md#code-generation), and hence which topics are available for ROS 2 applications to subscribe or publish (by default).
This document shows a markdown-rendered version of [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), listing the publications, subscriptions, and so on.
## Publications
| Topic | Тип | Rate Limit |
| --------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -------------------- |
| `/fmu/out/register_ext_component_reply` | [px4_msgs::msg::RegisterExtComponentReply](../msg_docs/RegisterExtComponentReply.md) | |
| `/fmu/out/arming_check_request` | [px4_msgs::msg::ArmingCheckRequest](../msg_docs/ArmingCheckRequest.md) | 5.0 |
| `/fmu/out/mode_completed` | [px4_msgs::msg::ModeCompleted](../msg_docs/ModeCompleted.md) | 50.0 |
| `/fmu/out/battery_status` | [px4_msgs::msg::BatteryStatus](../msg_docs/BatteryStatus.md) | 1.0 |
| `/fmu/out/collision_constraints` | [px4_msgs::msg::CollisionConstraints](../msg_docs/CollisionConstraints.md) | 50.0 |
| `/fmu/out/estimator_status_flags` | [px4_msgs::msg::EstimatorStatusFlags](../msg_docs/EstimatorStatusFlags.md) | 5.0 |
| `/fmu/out/failsafe_flags` | [px4_msgs::msg::FailsafeFlags](../msg_docs/FailsafeFlags.md) | 5.0 |
| `/fmu/out/manual_control_setpoint` | [px4_msgs::msg::ManualControlSetpoint](../msg_docs/ManualControlSetpoint.md) | 25.0 |
| `/fmu/out/message_format_response` | [px4_msgs::msg::MessageFormatResponse](../msg_docs/MessageFormatResponse.md) | |
| `/fmu/out/position_setpoint_triplet` | [px4_msgs::msg::PositionSetpointTriplet](../msg_docs/PositionSetpointTriplet.md) | 5.0 |
| `/fmu/out/sensor_combined` | [px4_msgs::msg::SensorCombined](../msg_docs/SensorCombined.md) | |
| `/fmu/out/timesync_status` | [px4_msgs::msg::TimesyncStatus](../msg_docs/TimesyncStatus.md) | 10.0 |
| `/fmu/out/vehicle_land_detected` | [px4_msgs::msg::VehicleLandDetected](../msg_docs/VehicleLandDetected.md) | 5.0 |
| `/fmu/out/vehicle_attitude` | [px4_msgs::msg::VehicleAttitude](../msg_docs/VehicleAttitude.md) | |
| `/fmu/out/vehicle_control_mode` | [px4_msgs::msg::VehicleControlMode](../msg_docs/VehicleControlMode.md) | 50.0 |
| `/fmu/out/vehicle_command_ack` | [px4_msgs::msg::VehicleCommandAck](../msg_docs/VehicleCommandAck.md) | |
| `/fmu/out/vehicle_global_position` | [px4_msgs::msg::VehicleGlobalPosition](../msg_docs/VehicleGlobalPosition.md) | 50.0 |
| `/fmu/out/vehicle_gps_position` | [px4_msgs::msg::SensorGps](../msg_docs/SensorGps.md) | 50.0 |
| `/fmu/out/vehicle_local_position` | [px4_msgs::msg::VehicleLocalPosition](../msg_docs/VehicleLocalPosition.md) | 50.0 |
| `/fmu/out/vehicle_odometry` | [px4_msgs::msg::VehicleOdometry](../msg_docs/VehicleOdometry.md) | |
| `/fmu/out/vehicle_status` | [px4_msgs::msg::VehicleStatus](../msg_docs/VehicleStatus.md) | 5.0 |
| `/fmu/out/airspeed_validated` | [px4_msgs::msg::AirspeedValidated](../msg_docs/AirspeedValidated.md) | 50.0 |
| `/fmu/out/vtol_vehicle_status` | [px4_msgs::msg::VtolVehicleStatus](../msg_docs/VtolVehicleStatus.md) | |
| `/fmu/out/home_position` | [px4_msgs::msg::HomePosition](../msg_docs/HomePosition.md) | 5.0 |
## Subscriptions
| Topic | Тип |
| ------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| /fmu/in/register_ext_component_request | [px4_msgs::msg::RegisterExtComponentRequest](../msg_docs/RegisterExtComponentRequest.md) |
| /fmu/in/unregister_ext_component | [px4_msgs::msg::UnregisterExtComponent](../msg_docs/UnregisterExtComponent.md) |
| /fmu/in/config_overrides_request | [px4_msgs::msg::ConfigOverrides](../msg_docs/ConfigOverrides.md) |
| /fmu/in/arming_check_reply | [px4_msgs::msg::ArmingCheckReply](../msg_docs/ArmingCheckReply.md) |
| /fmu/in/message_format_request | [px4_msgs::msg::MessageFormatRequest](../msg_docs/MessageFormatRequest.md) |
| /fmu/in/mode_completed | [px4_msgs::msg::ModeCompleted](../msg_docs/ModeCompleted.md) |
| /fmu/in/config_control_setpoints | [px4_msgs::msg::VehicleControlMode](../msg_docs/VehicleControlMode.md) |
| /fmu/in/distance_sensor | [px4_msgs::msg::DistanceSensor](../msg_docs/DistanceSensor.md) |
| /fmu/in/manual_control_input | [px4_msgs::msg::ManualControlSetpoint](../msg_docs/ManualControlSetpoint.md) |
| /fmu/in/offboard_control_mode | [px4_msgs::msg::OffboardControlMode](../msg_docs/OffboardControlMode.md) |
| /fmu/in/onboard_computer_status | [px4_msgs::msg::OnboardComputerStatus](../msg_docs/OnboardComputerStatus.md) |
| /fmu/in/obstacle_distance | [px4_msgs::msg::ObstacleDistance](../msg_docs/ObstacleDistance.md) |
| /fmu/in/sensor_optical_flow | [px4_msgs::msg::SensorOpticalFlow](../msg_docs/SensorOpticalFlow.md) |
| /fmu/in/goto_setpoint | [px4_msgs::msg::GotoSetpoint](../msg_docs/GotoSetpoint.md) |
| /fmu/in/telemetry_status | [px4_msgs::msg::TelemetryStatus](../msg_docs/TelemetryStatus.md) |
| /fmu/in/trajectory_setpoint | [px4_msgs::msg::TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) |
| /fmu/in/vehicle_attitude_setpoint | [px4_msgs::msg::VehicleAttitudeSetpoint](../msg_docs/VehicleAttitudeSetpoint.md) |
| /fmu/in/vehicle_mocap_odometry | [px4_msgs::msg::VehicleOdometry](../msg_docs/VehicleOdometry.md) |
| /fmu/in/vehicle_rates_setpoint | [px4_msgs::msg::VehicleRatesSetpoint](../msg_docs/VehicleRatesSetpoint.md) |
| /fmu/in/vehicle_visual_odometry | [px4_msgs::msg::VehicleOdometry](../msg_docs/VehicleOdometry.md) |
| /fmu/in/vehicle_command | [px4_msgs::msg::VehicleCommand](../msg_docs/VehicleCommand.md) |
| /fmu/in/vehicle_command_mode_executor | [px4_msgs::msg::VehicleCommand](../msg_docs/VehicleCommand.md) |
| /fmu/in/vehicle_thrust_setpoint | [px4_msgs::msg::VehicleThrustSetpoint](../msg_docs/VehicleThrustSetpoint.md) |
| /fmu/in/vehicle_torque_setpoint | [px4_msgs::msg::VehicleTorqueSetpoint](../msg_docs/VehicleTorqueSetpoint.md) |
| /fmu/in/actuator_motors | [px4_msgs::msg::ActuatorMotors](../msg_docs/ActuatorMotors.md) |
| /fmu/in/actuator_servos | [px4_msgs::msg::ActuatorServos](../msg_docs/ActuatorServos.md) |
| /fmu/in/aux_global_position | [px4_msgs::msg::VehicleGlobalPosition](../msg_docs/VehicleGlobalPosition.md) |
| /fmu/in/fixed_wing_longitudinal_setpoint | [px4_msgs::msg::FixedWingLongitudinalSetpoint](../msg_docs/FixedWingLongitudinalSetpoint.md) |
| /fmu/in/fixed_wing_lateral_setpoint | [px4_msgs::msg::FixedWingLateralSetpoint](../msg_docs/FixedWingLateralSetpoint.md) |
| /fmu/in/longitudinal_control_configuration | [px4_msgs::msg::LongitudinalControlConfiguration](../msg_docs/LongitudinalControlConfiguration.md) |
| /fmu/in/lateral_control_configuration | [px4_msgs::msg::LateralControlConfiguration](../msg_docs/LateralControlConfiguration.md) |
## Subscriptions Multi
None
## Not Exported
These messages are not listed in the yaml file.
They are not build into the module, and hence are neither published or subscribed.
:::details
See messages
- [SensorCorrection](../msg_docs/SensorCorrection.md)
- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md)
- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md)
- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md)
- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md)
- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md)
- [Px4ioStatus](../msg_docs/Px4ioStatus.md)
- [SatelliteInfo](../msg_docs/SatelliteInfo.md)
- [GeofenceResult](../msg_docs/GeofenceResult.md)
- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md)
- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md)
- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md)
- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md)
- [EventV0](../msg_docs/EventV0.md)
- [QshellRetval](../msg_docs/QshellRetval.md)
- [RoverThrottleSetpoint](../msg_docs/RoverThrottleSetpoint.md)
- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md)
- [RcChannels](../msg_docs/RcChannels.md)
- [SensorAccel](../msg_docs/SensorAccel.md)
- [GimbalDeviceAttitudeStatus](../msg_docs/GimbalDeviceAttitudeStatus.md)
- [EscStatus](../msg_docs/EscStatus.md)
- [RoverAttitudeSetpoint](../msg_docs/RoverAttitudeSetpoint.md)
- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md)
- [AirspeedWind](../msg_docs/AirspeedWind.md)
- [InputRc](../msg_docs/InputRc.md)
- [GpioIn](../msg_docs/GpioIn.md)
- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md)
- [VehicleImu](../msg_docs/VehicleImu.md)
- [Event](../msg_docs/Event.md)
- [SensorUwb](../msg_docs/SensorUwb.md)
- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md)
- [DatamanResponse](../msg_docs/DatamanResponse.md)
- [OrbTest](../msg_docs/OrbTest.md)
- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md)
- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md)
- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md)
- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md)
- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md)
- [TakeoffStatus](../msg_docs/TakeoffStatus.md)
- [UlogStreamAck](../msg_docs/UlogStreamAck.md)
- [OrbTestLarge](../msg_docs/OrbTestLarge.md)
- [RoverSteeringSetpoint](../msg_docs/RoverSteeringSetpoint.md)
- [CameraCapture](../msg_docs/CameraCapture.md)
- [VehicleRoi](../msg_docs/VehicleRoi.md)
- [ActuatorArmed](../msg_docs/ActuatorArmed.md)
- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md)
- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md)
- [GeofenceStatus](../msg_docs/GeofenceStatus.md)
- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md)
- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md)
- [PowerMonitor](../msg_docs/PowerMonitor.md)
- [RoverVelocityStatus](../msg_docs/RoverVelocityStatus.md)
- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md)
- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md)
- [TecsStatus](../msg_docs/TecsStatus.md)
- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md)
- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md)
- [Ping](../msg_docs/Ping.md)
- [LedControl](../msg_docs/LedControl.md)
- [Wind](../msg_docs/Wind.md)
- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md)
- [ActuatorTest](../msg_docs/ActuatorTest.md)
- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md)
- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md)
- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md)
- [Gripper](../msg_docs/Gripper.md)
- [SensorMag](../msg_docs/SensorMag.md)
- [DebugValue](../msg_docs/DebugValue.md)
- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md)
- [RcParameterMap](../msg_docs/RcParameterMap.md)
- [LandingGear](../msg_docs/LandingGear.md)
- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md)
- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md)
- [UlogStream](../msg_docs/UlogStream.md)
- [GimbalControls](../msg_docs/GimbalControls.md)
- [RoverRateSetpoint](../msg_docs/RoverRateSetpoint.md)
- [LogMessage](../msg_docs/LogMessage.md)
- [RoverVelocitySetpoint](../msg_docs/RoverVelocitySetpoint.md)
- [GpioOut](../msg_docs/GpioOut.md)
- [TaskStackInfo](../msg_docs/TaskStackInfo.md)
- [VelocityLimits](../msg_docs/VelocityLimits.md)
- [MagWorkerData](../msg_docs/MagWorkerData.md)
- [ParameterUpdate](../msg_docs/ParameterUpdate.md)
- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md)
- [SensorBaro](../msg_docs/SensorBaro.md)
- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md)
- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md)
- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md)
- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md)
- [Rpm](../msg_docs/Rpm.md)
- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md)
- [MountOrientation](../msg_docs/MountOrientation.md)
- [ActionRequest](../msg_docs/ActionRequest.md)
- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md)
- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md)
- [LoggerStatus](../msg_docs/LoggerStatus.md)
- [GeneratorStatus](../msg_docs/GeneratorStatus.md)
- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md)
- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md)
- [LandingTargetPose](../msg_docs/LandingTargetPose.md)
- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md)
- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md)
- [OrbitStatus](../msg_docs/OrbitStatus.md)
- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md)
- [EstimatorStatus](../msg_docs/EstimatorStatus.md)
- [DatamanRequest](../msg_docs/DatamanRequest.md)
- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md)
- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md)
- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md)
- [Cpuload](../msg_docs/Cpuload.md)
- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md)
- [RoverRateStatus](../msg_docs/RoverRateStatus.md)
- [EscReport](../msg_docs/EscReport.md)
- [DebugArray](../msg_docs/DebugArray.md)
- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md)
- [SensorHygrometer](../msg_docs/SensorHygrometer.md)
- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md)
- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md)
- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md)
- [QshellReq](../msg_docs/QshellReq.md)
- [CameraStatus](../msg_docs/CameraStatus.md)
- [GpsInjectData](../msg_docs/GpsInjectData.md)
- [FigureEightStatus](../msg_docs/FigureEightStatus.md)
- [TransponderReport](../msg_docs/TransponderReport.md)
- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md)
- [MavlinkLog](../msg_docs/MavlinkLog.md)
- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md)
- [FuelTankStatus](../msg_docs/FuelTankStatus.md)
- [Mission](../msg_docs/Mission.md)
- [PositionSetpoint](../msg_docs/PositionSetpoint.md)
- [MissionResult](../msg_docs/MissionResult.md)
- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md)
- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md)
- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md)
- [DifferentialPressure](../msg_docs/DifferentialPressure.md)
- [CellularStatus](../msg_docs/CellularStatus.md)
- [GpsDump](../msg_docs/GpsDump.md)
- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md)
- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md)
- [NavigatorStatus](../msg_docs/NavigatorStatus.md)
- [RoverPositionSetpoint](../msg_docs/RoverPositionSetpoint.md)
- [FollowTarget](../msg_docs/FollowTarget.md)
- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md)
- [EstimatorStates](../msg_docs/EstimatorStates.md)
- [SensorGyro](../msg_docs/SensorGyro.md)
- [SensorAirflow](../msg_docs/SensorAirflow.md)
- [ButtonEvent](../msg_docs/ButtonEvent.md)
- [DebugKeyValue](../msg_docs/DebugKeyValue.md)
- [GpioConfig](../msg_docs/GpioConfig.md)
- [CameraTrigger](../msg_docs/CameraTrigger.md)
- [LandingGearWheel](../msg_docs/LandingGearWheel.md)
- [VehicleConstraints](../msg_docs/VehicleConstraints.md)
- [HealthReport](../msg_docs/HealthReport.md)
- [PowerButtonState](../msg_docs/PowerButtonState.md)
- [RadioStatus](../msg_docs/RadioStatus.md)
- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md)
- [EstimatorBias](../msg_docs/EstimatorBias.md)
- [DebugVect](../msg_docs/DebugVect.md)
- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md)
- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md)
- [PpsCapture](../msg_docs/PpsCapture.md)
- [SensorSelection](../msg_docs/SensorSelection.md)
- [SystemPower](../msg_docs/SystemPower.md)
- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md)
- [SensorGyroFft](../msg_docs/SensorGyroFft.md)
- [VehicleAirData](../msg_docs/VehicleAirData.md)
- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md)
- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md)
- [GpioRequest](../msg_docs/GpioRequest.md)
- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md)
- [RtlStatus](../msg_docs/RtlStatus.md)
- [Airspeed](../msg_docs/Airspeed.md)
- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md)
- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md)
- [IrlockReport](../msg_docs/IrlockReport.md)
- [HeaterStatus](../msg_docs/HeaterStatus.md)
- [AdcReport](../msg_docs/AdcReport.md)
- [PwmInput](../msg_docs/PwmInput.md)
- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md)
- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md)
- [OrbTestMedium](../msg_docs/OrbTestMedium.md)
- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md)
- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md)
- [TuneControl](../msg_docs/TuneControl.md)
- [WheelEncoders](../msg_docs/WheelEncoders.md)
- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md)
- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md)
- [SensorsStatus](../msg_docs/SensorsStatus.md)
:::
+24 -5
View File
@@ -61,12 +61,12 @@ For example the [VelocityLimits](../msg_docs/VelocityLimits.md) message definiti
```text
# Velocity and yaw rate limits for a multicopter position slow mode only
uint64 timestamp # time since system start (microseconds)
uint64 timestamp # [us] Time since system start.
# absolute speeds, NAN means use default limit
float32 horizontal_velocity # [m/s]
float32 vertical_velocity # [m/s]
float32 yaw_rate # [rad/s]
float32 horizontal_velocity # [m/s] Horizontal velocity.
float32 vertical_velocity # [m/s] Vertical velocity.
float32 yaw_rate # [rad/s] Yaw rate.
```
By default this message definition will be compiled to a single topic with an id `velocity_limits`, a direct conversion from the CamelCase name to a snake_case version.
@@ -92,15 +92,34 @@ To nest a message, simply include the nested message type in the parent message
```text
# Global position setpoint triplet in WGS84 coordinates.
#
# This are the three next waypoints (or just the next two or one).
uint64 timestamp # time since system start (microseconds)
uint64 timestamp # [us] Time since system start.
PositionSetpoint previous
PositionSetpoint current
PositionSetpoint next
```
### uORB Buffer Length (ORB_QUEUE_LENGTH)
uORB messages have a single-message buffer by default, which may be overwritten if the message publication rate is too high.
In most cases this does not matter: either we are only interested in the latest sample of a topic, such as a sensor value or a setpoint, or losing a few samples is not a particular problem.
For relatively few cases, such as vehicle commands, it is important that we don't drop topics.
In order to reduce the chance that messages will be dropped we can use named constant `ORB_QUEUE_LENGTH` to create a buffer of the specified length.
For example, to create a four-message queue, add the following line to your message definition:
```sh
uint8 ORB_QUEUE_LENGTH = 4
```
As long as subscribers are able to read messages out of the buffer quickly enough than it isn't ever fully filled to the queue length (by publishers), they will be able to get all messages that are sent.
Messages will still be lost they are published when the queue is filled.
Note that the queue length value must be a power of 2 (so 2, 4, 8, ...).
### Message/Field Deprecation {#deprecation}
As there are external tools using uORB messages from log files, such as [Flight Review](https://github.com/PX4/flight_review), certain aspects need to be considered when updating existing messages:
+46 -48
View File
@@ -38,7 +38,7 @@ The PX4 [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) is gen
Агент не залежить від клієнтського коду.
Він може бути побудований окремо або в робочому просторі ROS 2, або встановлений як snap пакет в Ubuntu.
When PX4 is built, a code generator uses the uORB message definitions in the source tree ([PX4-Autopilot/msg](https://github.com/PX4/PX4-Autopilot/tree/main/msg)) to compile support for the subset of uORB topics in [PX4-Autopilot/src/modules/uxrce_dds_client/dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) into [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client).
When PX4 is built, a code generator uses the uORB message definitions in the source tree ([PX4-Autopilot/msg](https://github.com/PX4/PX4-Autopilot/tree/main/msg)) to compile support for the subset of uORB topics in [/src/modules/uxrce_dds_client/dds_topics.yaml](../middleware/dds_topics.md) into [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client).
PX4 main or release builds automatically export the set of uORB messages definitions in the build to an associated branch in [PX4/px4_msgs](https://github.com/PX4/px4_msgs).
@@ -326,13 +326,11 @@ ROS_DOMAIN_ID=3 PX4_UXRCE_DDS_PORT=9999 PX4_UXRCE_DDS_NS=drone make px4_sitl gz_
## Підтримувані повідомлення uORB
The set of [PX4 uORB topics](../msg_docs/index.md) that are exposed through the client are set in [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml).
The set of [PX4 uORB topics](../msg_docs/index.md) that are exposed through the client are set in [dds_topics.yaml](../middleware/dds_topics.md).
The topics are release specific (support is compiled into [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) at build time).
Хоча більшість випусків мають підтримувати дуже схожий набір повідомлень, щоб бути впевненими, вам слід перевірити файл yaml для вашого конкретного релізу.
<!-- Jublish the set we use?: https://github.com/PX4/px4_msgs/issues/22 -->
Note that ROS 2/DDS needs to have the _same_ message definitions that were used to create the uXRCE-DDS client module in the PX4 Firmware in order to interpret the messages.
The message definitions are stored in the ROS 2 interface package [PX4/px4_msgs](https://github.com/PX4/px4_msgs), and they are automatically synchronized by CI on the `main` and release branches.
Note that all the messages from PX4 source code are present in the repository, but only those listed in `dds_topics.yaml` will be available as ROS 2 topics.
@@ -349,21 +347,21 @@ Note that all the messages from PX4 source code are present in the repository, b
```
::: info
Technically, [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) completely defines the relationship between PX4 uORB topics and ROS 2 messages.
Technically, [dds_topics.yaml](../middleware/dds_topics.md) completely defines the relationship between PX4 uORB topics and ROS 2 messages.
For more information see [DDS Topics YAML](#dds-topics-yaml) below.
:::
## Customizing the Namespace
Custom topic and service namespaces can be applied at build time (changing [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml)) or at runtime (which is useful for multi vehicle operations):
Custom topic and service namespaces can be applied at build time (changing [dds_topics.yaml](../middleware/dds_topics.md)) or at runtime (which is useful for multi vehicle operations):
- One possibility is to use the `-n` option when starting the [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) from command line.
Ця техніка може бути використана як у симуляторах, так і на реальних транспортних засобах.
- A custom namespace can be provided for simulations (only) by setting the environment variable `PX4_UXRCE_DDS_NS` before starting the simulation.
:::info
Changing the namespace at runtime will append the desired namespace as a prefix to all `topic` fields in [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) and all [service servers](#dds-ros-2-services).
Changing the namespace at runtime will append the desired namespace as a prefix to all `topic` fields in [dds_topics.yaml](../middleware/dds_topics.md) and all [service servers](#dds-ros-2-services).
Отже, команди, подібні до:
```sh
@@ -385,13 +383,13 @@ PX4_UXRCE_DDS_NS=uav_1 make px4_sitl gz_x500
:::
## Налаштування PX4 ROS 2 QoS
## PX4 ROS 2 QoS Settings
Налаштування QoS PX4 для видавців несумісні з налаштуваннями QoS за замовчуванням для підписників ROS 2.
Таким чином, якщо код ROS 2 потрібно підписатися на тему uORB, йому потрібно використовувати сумісні налаштування QoS.
PX4 QoS settings for publishers are incompatible with the default QoS settings for ROS 2 subscribers.
So if ROS 2 code needs to subscribe to a uORB topic, it will need to use compatible QoS settings.
One example of which is shown in [ROS 2 User Guide > ROS 2 Subscriber QoS Settings](../ros2/user_guide.md#ros-2-subscriber-qos-settings).
PX4 використовує наступні параметри QoS для видавців:
PX4 uses the following QoS settings for publishers:
```cpp
uxrQoS_t qos = {
@@ -402,7 +400,7 @@ uxrQoS_t qos = {
};
```
PX4 використовує наступні параметри QoS для підписників:
PX4 uses the following QoS settings for subscribers:
```cpp
uxrQoS_t qos = {
@@ -413,17 +411,17 @@ uxrQoS_t qos = {
};
```
ROS 2 використовує наступні налаштування QoS (за замовчуванням) для видавців та підписок: «зберігати останніми» для історії з розміром черги 10, «reliable» для надійності, «volatile» для тривалості і «system default» для життєздатності.
Дедлайн, тривалість життя та оренда також налаштовані на "за замовчуванням".
ROS 2 uses the following QoS settings (by default) for publishers and subscriptions: "keep last" for history with a queue size of 10, "reliable" for reliability, "volatile" for durability, and "system default" for liveliness.
Deadline, lifespan, and lease durations are also all set to "default".
<!-- From https://github.com/PX4/PX4-user_guide/pull/2259#discussion_r1099788316 -->
## DDS теми YAML
## DDS Topics YAML
The PX4 yaml file [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) defines the set of PX4 uORB topics that are built into firmware and published.
Точніше, він повністю визначає взаємозв'язок/сполучення між повідомленнями PX4 uORB і ROS 2.
The PX4 [dds_topics.yaml](../middleware/dds_topics.md) file defines the set of PX4 uORB topics that are built into firmware and published.
More precisely, it completely defines the relationship/pairing between PX4 uORB and ROS 2 messages.
Файл структурований наступним чином:
The file is structured as follows:
```yaml
publications:
@@ -471,7 +469,7 @@ Each (`topic`,`type`) pairs defines:
It is identified by the last token in `topic:` that starts with `/` and does not contains any `/` in it.
`vehicle_odometry`, `vehicle_status` and `offboard_control_mode` are examples of base names.
3. The topic [namespace](https://design.ros2.org/articles/topic_and_service_names.html#namespaces).
За замовчуванням встановлено ​​на:
By default it is set to:
- `/fmu/out/` for topics that are _published_ by PX4.
- `/fmu/in/` for topics that are _subscribed_ by PX4.
4. The message type (`VehicleOdometry`, `VehicleStatus`, `OffboardControlMode`, etc.) and the ROS 2 package (`px4_msgs`) that is expected to provide the message definition.
@@ -485,22 +483,22 @@ Add a topic to the `subscriptions` section to:
- Create a unidirectional route going from the ROS2 topic to the _default_ instance (instance 0) of the associated uORB topic.
For example, it creates a ROS2 subscriber of `/fmu/in/vehicle_odometry` and a uORB publisher of `vehicle_odometry`.
- Якщо інші (внутрішні) модулі PX4 вже публікують у тому ж екземплярі теми uORB, що й публікатор ROS2, підписники цього екземпляра будуть отримувати всі потоки повідомлень.
Підписник uORB не зможе визначити, чи вхідне повідомлення було опубліковане PX4 або ROS2.
- Це бажана поведінка, коли очікується, що ROS2-видавець буде єдиним видавцем у екземплярі теми (наприклад, для заміни внутрішнього видавця теми під час автономного керування), або коли джерело декількох потоків публікацій не має значення.
- If other (internal) PX4 modules are already publishing on the same uORB topic instance as the ROS2 publisher, the instance's subscribers will receive all streams of messages.
The uORB subscriber will not be able to determine if an incoming message was published by PX4 or by ROS2.
- This is the desired behavior when the ROS2 publisher is expected to be the sole publisher on the topic instance (for example, replacing an internal publisher to the topic during offboard control), or when the source of multiple publishing streams does not matter.
Add a topic to the `subscriptions_multi` section to:
- Create a unidirectional route going from the ROS2 topic to a _new_ instance of the associated uORB topic.
For example, if `vehicle_odometry` has already `2` instances, it creates a ROS2 subscriber of `/fmu/in/vehicle_odometry` and a uORB publisher on instance `3` of `vehicle_odometry`.
- Це гарантує, що жоден інший внутрішній модуль PX4 не публікуватиметься на тому самому екземплярі, що використовується uXRCE-DDS.
Підписники зможуть підписатися на потрібний екземпляр і розрізняти видавців.
- Зауважте, однак, що це гарантує розділення між видавцями PX4 і ROS2, а не між кількома видавцями ROS2.
У цьому випадку їхні повідомлення все одно будуть перенаправлені на той самий екземпляр.
- Це бажана поведінка, наприклад, коли ви хочете, щоб PX4 реєстрував показання двох однакових датчиків; вони обидва публікуватимуться в одній темі, але один з них використовуватиме екземпляр 0, а інший - екземпляр 1.
- This ensures that no other internal PX4 module will publish on the same instance used by uXRCE-DDS.
The subscribers will be able to subscribe to the desired instance and distinguish between publishers.
- Note, however, that this guarantees separation between PX4 and ROS2 publishers, not among multiple ROS2 publishers.
In that scenario, their messages will still be routed to the same instance.
- This is the desired behavior, for example, when you want PX4 to log the readings of two equal sensors; they will both publish on the same topic, but one will use instance 0 and the other will use instance 1.
Ви можете довільно змінювати конфігурацію.
Наприклад, ви можете використовувати різні простори імен за замовчуванням або використовувати власний пакет для зберігання визначень повідомлень.
You can arbitrarily change the configuration.
For example, you could use different default namespaces or use a custom package to store the message definitions.
## DDS (ROS 2) Services
@@ -513,62 +511,62 @@ For example, the `/fmu/vehicle_command` service server defined in [`px4_msgs::sr
For a list of services, details and examples see the [service documentation](../ros2/user_guide.md#px4-ros-2-service-servers) in the ROS 2 User Guide.
## Посібник міграції з Fast-RTPS на uXRCE-DDS
## Fast-RTPS to uXRCE-DDS Migration Guidelines
These guidelines explain how to migrate from using PX4 v1.13 [Fast-RTPS](../middleware/micrortps.md) middleware to PX4 v1.14 `uXRCE-DDS` middleware.
These are useful if you have [ROS 2 applications written for PX4 v1.13](https://docs.px4.io/v1.13/en/ros/ros2_comm.html), or you have used Fast-RTPS to interface your applications to PX4 [directly](https://docs.px4.io/v1.13/en/middleware/micrortps.html#agent-in-an-offboard-fast-dds-interface-ros-independent).
:::info
This section contains migration-specific information.
Вам також слід прочитати решту цієї сторінки, щоб правильно зрозуміти uXRCE-DDS.
You should also read the rest of this page to properly understand uXRCE-DDS.
:::
#### Залежності не потрібно видаляти
#### Dependencies do not need to be removed
uXRCE-DDS does not need the dependencies that were required for Fast-RTPS, such as those installed by following the topic [Fast DDS Installation](https://docs.px4.io/v1.13/en/dev_setup/fast-dds-installation.html).
Ви можете зберегти їх, якщо хочете, не впливаючи на ваші додатки uXRCE-DDS.
You can keep them if you want, without affecting your uXRCE-DDS applications.
Якщо ви вирішили видалити залежності, будьте обережні, щоб не видалити нічого, що використовується програмами (наприклад, Java).
If you do choose to remove the dependencies, take care not to remove anything that is used by applications (for example, Java).
#### `_rtps` targets have been removed
Anywhere you previously used a build target with extension `_rtps`, such as `px4_fmu-v5_rtps` or `px4_sitl_rtps`, you can now use the equivalent default target (for these cases `px4_fmu-v5_default` and `px4_sitl_default`).
The make targets with extension `_rtps` were used to build firmware that included client side RTPS code.
Проміжне програмне забезпечення uXRCE-DDS за замовчуванням включено до збірок для більшості плат, тому вам більше не потрібна спеціальна прошивка для роботи з ROS 2.
The uXRCE-DDS middleware is included by default in builds for most boards, so you no longer need a special firmware to work with ROS 2.
To check if your board has the middleware, look for `CONFIG_MODULES_UXRCE_DDS_CLIENT=y` in the `.px4board` file of your board.
Those files are nested in [PX4-Autopilot/boards](https://github.com/PX4/PX4-Autopilot/tree/main/boards).
If it is not present, or if it is set to `n`, then you have to clone the PX4 repo, modify the board configuration and manually [compile](../dev_setup/building_px4.md) the firmware.
#### Новий модуль клієнта та нові параметри запуску
#### New client module and new start parameters
Оскільки клієнт реалізовано новим модулем PX4, тепер у вас є нові параметри для його запуску.
As the client is implemented by a new PX4 module, you now have new parameters to start it.
Take a look at the [client startup section](#starting-the-client) to learn how this is done.
#### Новий файл для налаштування того, які теми публікуються
#### New file for setting which topics are published
The list of topics that are published and subscribed for a particular firmware is now managed by the [dds_topic.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) configuration file, which replaces [urtps_bridge_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/release/1.13/msg/tools/urtps_bridge_topics.yaml)
The list of topics that are published and subscribed for a particular firmware is now managed by the [dds_topics.yaml](../middleware/dds_topics.md) configuration file, which replaces [urtps_bridge_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/release/1.13/msg/tools/urtps_bridge_topics.yaml)
See [Supported uORB Messages](#supported-uorb-messages) and [DDS Topics YAML](#dds-topics-yaml) sections for more information.
#### Теми більше не потрібно синхронізувати між клієнтом і агентом.
#### Topics no longer need to be synced between client and agent.
The list of bridged topics between agent and client no longer needs to be synced for ROS 2, so the `update_px4_ros2_bridge.sh` script is no longer needed.
#### Налаштування назви теми за замовчуванням змінено
#### Default topic naming convention has changed
Змінився формат назв тем:
The topic naming format changed:
- Published topics: `/fmu/topic-name/out` (Fast-RTPS) to `/fmu/out/topic-name` (XRCE-DDS).
- Subscribed topics: `/fmu/topic-name/in`(Fast-RTPS) to `/fmu/in/topic-name` (XRCE-DDS).
Вам слід оновити свій додаток відповідно до нової конвенції.
You should update your application to the new convention.
:::info
You might also edit [dds_topic.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) to revert to the old convention.
Це не рекомендується, оскільки це означає, що вам доведеться завжди використовувати кастомну прошивку.
This is not recommended because it means that you would have to always use custom firmware.
:::
#### XRCE-DDS-Agent
@@ -576,18 +574,18 @@ You might also edit [dds_topic.yaml](https://github.com/PX4/PX4-Autopilot/blob/m
The XRCE-DDS agent is "generic" and independent of PX4: [micro-xrce-dds-agent](https://micro-xrce-dds.docs.eprosima.com/en/latest/agent.html).
There are many ways to install it on your PC / companion computer - for more information see the [dedicated section](#micro-xrce-dds-agent-installation).
#### Зміни, що стосуються конкретних додатків
#### Application-Specific Changes
If you where not using ROS 2 alongside the agent ([Fast DDS Interface ROS-Independent](https://docs.px4.io/v1.13/en/middleware/micrortps.html#agent-in-an-offboard-fast-dds-interface-ros-independent)), then you need to migrate to [eProsima Fast DDS](https://fast-dds.docs.eprosima.com/en/latest/index.html).
ROS 2 applications still need to compile alongside the PX4 messages, which you do by adding the [px4_msgs](https://github.com/PX4/px4_msgs) package to your workspace.
You can remove the [px4_ros_com](https://github.com/PX4/px4_ros_com) package as it is no longer needed, other than for example code.
У ваших вузлах ROS 2 вам знадобиться:
In your ROS 2 nodes, you will need to:
- Update the [QoS](#px4-ros-2-qos-settings) of your publishers and subscribers as PX4 does not use the ROS 2 default settings.
- Change the names of your topics, unless you edited [dds_topic.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml).
- Видаліть все, що стосується синхронізації часу, оскільки XRCE-DDS автоматично піклується про синхронізацію часу агента/клієнта.
- Remove everything related to time synchronization, as XRCE-DDS automatically takes care of agent/client time synchronization.
In C++ applications you can set the `timestamp` field of your messages like this:
@@ -601,7 +599,7 @@ You can remove the [px4_ros_com](https://github.com/PX4/px4_ros_com) package as
msg.timestamp = int(self.get_clock().now().nanoseconds / 1000)
```
## Корисні ресурси
## Helpful Resources
- [ROS 2 in PX4: Technical Details of a Seamless Transition to XRCE-DDS](https://www.youtube.com/watch?v=F5oelooT67E) - Pablo Garrido & Nuno Marques (youtube)
- [PX4 ROS 2 offboard tutorial](https://gist.github.com/julianoes/adbf76408663829cd9aed8d14c88fa29) (Github gist - JulianOes)
+138 -138
View File
@@ -28,7 +28,7 @@ The agent acts as a proxy for the client to publish and subscribe to topics in t
The PX4 [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) is generated at build time and included in PX4 firmware by default.
It includes both the "generic" micro XRCE-DDS client code, and PX4-specific translation code that it uses to publish to/from uORB topics.
The subset of uORB messages that are generated into the client are listed in [PX4-Autopilot/src/modules/uxrce_dds_client/dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml).
The subset of uORB messages that are generated into the client are specified in [dds_topics.yaml](../middleware/dds_topics.md).
The generator uses the uORB message definitions in the source tree: [PX4-Autopilot/msg](https://github.com/PX4/PX4-Autopilot/tree/main/msg) to create the code for sending ROS 2 messages.
ROS 2 applications need to be built in a workspace that has the _same_ message definitions that were used to create the uXRCE-DDS client module in the PX4 Firmware.
@@ -97,48 +97,48 @@ To install ROS 2 and its dependencies:
1. Встановлення ROS 2.
:::: tabs
:::: tabs
::: tab humble
To install ROS 2 "Humble" on Ubuntu 22.04:
::: tab humble
To install ROS 2 "Humble" on Ubuntu 22.04:
```sh
sudo apt update && sudo apt install locales
sudo locale-gen en_US en_US.UTF-8
sudo update-locale LC_ALL=en_US.UTF-8 LANG=en_US.UTF-8
export LANG=en_US.UTF-8
sudo apt install software-properties-common
sudo add-apt-repository universe
sudo apt update && sudo apt install curl -y
sudo curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -o /usr/share/keyrings/ros-archive-keyring.gpg
echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/ros-archive-keyring.gpg] http://packages.ros.org/ros2/ubuntu $(. /etc/os-release && echo $UBUNTU_CODENAME) main" | sudo tee /etc/apt/sources.list.d/ros2.list > /dev/null
sudo apt update && sudo apt upgrade -y
sudo apt install ros-humble-desktop
sudo apt install ros-dev-tools
source /opt/ros/humble/setup.bash && echo "source /opt/ros/humble/setup.bash" >> .bashrc
```
```sh
sudo apt update && sudo apt install locales
sudo locale-gen en_US en_US.UTF-8
sudo update-locale LC_ALL=en_US.UTF-8 LANG=en_US.UTF-8
export LANG=en_US.UTF-8
sudo apt install software-properties-common
sudo add-apt-repository universe
sudo apt update && sudo apt install curl -y
sudo curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -o /usr/share/keyrings/ros-archive-keyring.gpg
echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/ros-archive-keyring.gpg] http://packages.ros.org/ros2/ubuntu $(. /etc/os-release && echo $UBUNTU_CODENAME) main" | sudo tee /etc/apt/sources.list.d/ros2.list > /dev/null
sudo apt update && sudo apt upgrade -y
sudo apt install ros-humble-desktop
sudo apt install ros-dev-tools
source /opt/ros/humble/setup.bash && echo "source /opt/ros/humble/setup.bash" >> .bashrc
```
The instructions above are reproduced from the official installation guide: [Install ROS 2 Humble](https://docs.ros.org/en/humble/Installation/Ubuntu-Install-Debians.html).
You can install _either_ the desktop (`ros-humble-desktop`) _or_ bare-bones versions (`ros-humble-ros-base`), _and_ the development tools (`ros-dev-tools`).
The instructions above are reproduced from the official installation guide: [Install ROS 2 Humble](https://docs.ros.org/en/humble/Installation/Ubuntu-Install-Debians.html).
You can install _either_ the desktop (`ros-humble-desktop`) _or_ bare-bones versions (`ros-humble-ros-base`), _and_ the development tools (`ros-dev-tools`).
:::
::: tab foxy
To install ROS 2 "Foxy" on Ubuntu 20.04:
::: tab foxy
To install ROS 2 "Foxy" on Ubuntu 20.04:
- Follow the official installation guide: [Install ROS 2 Foxy](https://docs.ros.org/en/foxy/Installation/Ubuntu-Install-Debians.html).
- Follow the official installation guide: [Install ROS 2 Foxy](https://docs.ros.org/en/foxy/Installation/Ubuntu-Install-Debians.html).
You can install _either_ the desktop (`ros-foxy-desktop`) _or_ bare-bones versions (`ros-foxy-ros-base`), _and_ the development tools (`ros-dev-tools`).
You can install _either_ the desktop (`ros-foxy-desktop`) _or_ bare-bones versions (`ros-foxy-ros-base`), _and_ the development tools (`ros-dev-tools`).
:::
::::
::::
2. Some Python dependencies must also be installed (using **`pip`** or **`apt`**):
```sh
pip install --user -U empy==3.3.4 pyros-genmsg setuptools
```
```sh
pip install --user -U empy==3.3.4 pyros-genmsg setuptools
```
### Setup Micro XRCE-DDS Agent & Client
@@ -155,22 +155,22 @@ To setup and start the agent:
2. Введіть наступні команди для витягування та побудови агента з вихідного коду:
```sh
git clone -b v2.4.2 https://github.com/eProsima/Micro-XRCE-DDS-Agent.git
cd Micro-XRCE-DDS-Agent
mkdir build
cd build
cmake ..
make
sudo make install
sudo ldconfig /usr/local/lib/
```
```sh
git clone -b v2.4.2 https://github.com/eProsima/Micro-XRCE-DDS-Agent.git
cd Micro-XRCE-DDS-Agent
mkdir build
cd build
cmake ..
make
sudo make install
sudo ldconfig /usr/local/lib/
```
3. Запустіть агента з налаштуваннями для підключення до клієнта uXRCE-DDS, який працює на симуляторі:
```sh
MicroXRCEAgent udp4 -p 8888
```
```sh
MicroXRCEAgent udp4 -p 8888
```
The agent is now running, but you won't see much until we start PX4 (in the next step).
@@ -187,31 +187,31 @@ To start the simulator (and client):
1. Open a new terminal in the root of the **PX4 Autopilot** repo that was installed above.
:::: tabs
:::: tabs
::: tab humble
::: tab humble
- Start a PX4 [Gazebo](../sim_gazebo_gz/index.md) simulation using:
- Start a PX4 [Gazebo](../sim_gazebo_gz/index.md) simulation using:
```sh
make px4_sitl gz_x500
```
```sh
make px4_sitl gz_x500
```
:::
::: tab foxy
::: tab foxy
- Start a PX4 [Gazebo Classic](../sim_gazebo_classic/index.md) simulation using:
- Start a PX4 [Gazebo Classic](../sim_gazebo_classic/index.md) simulation using:
```sh
make px4_sitl gazebo-classic
```
```sh
make px4_sitl gazebo-classic
```
:::
::::
::::
The agent and client are now running they should connect.
@@ -261,52 +261,52 @@ To create and build the workspace:
2. Створіть новий каталог робочого простору та перейдіть до нього за допомогою:
```sh
mkdir -p ~/ws_sensor_combined/src/
cd ~/ws_sensor_combined/src/
```
```sh
mkdir -p ~/ws_sensor_combined/src/
cd ~/ws_sensor_combined/src/
```
::: info
A naming convention for workspace folders can make it easier to manage workspaces.
::: info
A naming convention for workspace folders can make it easier to manage workspaces.
:::
3. Clone the example repository and [px4_msgs](https://github.com/PX4/px4_msgs) to the `/src` directory (the `main` branch is cloned by default, which corresponds to the version of PX4 we are running):
```sh
git clone https://github.com/PX4/px4_msgs.git
git clone https://github.com/PX4/px4_ros_com.git
```
```sh
git clone https://github.com/PX4/px4_msgs.git
git clone https://github.com/PX4/px4_ros_com.git
```
4. Source the ROS 2 development environment into the current terminal and compile the workspace using `colcon`:
:::: tabs
:::: tabs
::: tab humble
::: tab humble
```sh
cd ..
source /opt/ros/humble/setup.bash
colcon build
```
```sh
cd ..
source /opt/ros/humble/setup.bash
colcon build
```
:::
::: tab foxy
::: tab foxy
```sh
cd ..
source /opt/ros/foxy/setup.bash
colcon build
```
```sh
cd ..
source /opt/ros/foxy/setup.bash
colcon build
```
:::
::::
::::
This builds all the folders under `/src` using the sourced toolchain.
This builds all the folders under `/src` using the sourced toolchain.
#### Запуск прикладу
@@ -322,42 +322,42 @@ In a new terminal:
1. Перейдіть на верхній рівень каталогу вашого робочого простору та джерело середовища ROS 2 (у цьому випадку "Humble"):
:::: tabs
:::: tabs
::: tab humble
::: tab humble
```sh
cd ~/ws_sensor_combined/
source /opt/ros/humble/setup.bash
```
```sh
cd ~/ws_sensor_combined/
source /opt/ros/humble/setup.bash
```
:::
::: tab foxy
::: tab foxy
```sh
cd ~/ws_sensor_combined/
source /opt/ros/foxy/setup.bash
```
```sh
cd ~/ws_sensor_combined/
source /opt/ros/foxy/setup.bash
```
:::
::::
::::
2. Source the `local_setup.bash`.
```sh
source install/local_setup.bash
```
```sh
source install/local_setup.bash
```
3. Тепер запустіть приклад.
Note here that we use `ros2 launch`, which is described below.
Note here that we use `ros2 launch`, which is described below.
```sh
ros2 launch px4_ros_com sensor_combined_listener.launch.py
```
```sh
ros2 launch px4_ros_com sensor_combined_listener.launch.py
```
If this is working you should see data being printed on the terminal/console where you launched the ROS listener:
@@ -385,18 +385,18 @@ If you were to use incompatible [message versions](../middleware/uorb.md#message
1. Include the [Message Translation Node](../ros2/px4_ros2_msg_translation_node.md) into the example workspace or a separate workspace by running the following script:
```sh
cd /path/to/ros_ws
/path/to/PX4-Autopilot/Tools/copy_to_ros_ws.sh .
```
```sh
cd /path/to/ros_ws
/path/to/PX4-Autopilot/Tools/copy_to_ros_ws.sh .
```
2. Build and run the translation node:
```sh
colcon build
source install/local_setup.bash
ros2 run translation_node translation_node_bin
```
```sh
colcon build
source install/local_setup.bash
ros2 run translation_node translation_node_bin
```
## Керування Транспортним Засобом
@@ -405,7 +405,7 @@ To control applications, ROS 2 applications:
- підписатися на (слухати) тематичні теми, опубліковані PX4
- опублікувати у темах, які спонукають PX4 виконати певну дію.
The topics that you can use are defined in [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), and you can get more information about their data in the [uORB Message Reference](../msg_docs/index.md).
The topics that you can use are defined in [dds_topics.yaml](../middleware/dds_topics.md), and you can get more information about their data in the [uORB Message Reference](../msg_docs/index.md).
For example, [VehicleGlobalPosition](../msg_docs/VehicleGlobalPosition.md) can be used to get the vehicle global position, while [VehicleCommand](../msg_docs/VehicleCommand.md) can be used to command actions such as takeoff and land.
The [ROS 2 Example applications](#ros-2-example-applications) examples below provide concrete examples of how to use these topics.
@@ -456,13 +456,13 @@ Therefore, ROS 2 nodes that want to interface with PX4 must take care of the fra
- Для повороту вектора з ENU на NED потрібно виконати дві основні обертання:
- first a pi/2 rotation around the `Z`-axis (up),
- then a pi rotation around the `X`-axis (old East/new North).
- first a pi/2 rotation around the `Z`-axis (up),
- then a pi rotation around the `X`-axis (old East/new North).
- To rotate a vector from NED to ENU two basic rotations must be performed:
- - first a pi/2 rotation around the `Z`-axis (down),
- then a pi rotation around the `X`-axis (old North/new East). Note that the two resulting operations are mathematically equivalent.
- then a pi rotation around the `X`-axis (old North/new East). Note that the two resulting operations are mathematically equivalent.
- To rotate a vector from FLU to FRD a pi rotation around the `X`-axis (front) is sufficient.
@@ -720,17 +720,17 @@ Note that all the messages from PX4 source code are present in the repository, b
- If you're using a main or release version of PX4 you can get the message definitions by cloning the interface package [PX4/px4_msgs](https://github.com/PX4/px4_msgs) into your workspace.
- Якщо ви створюєте або змінюєте повідомлення uORB, вам потрібно вручну оновити повідомлення у вашому робочому просторі з вихідного дерева PX4.
Generally this means that you would update [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), clone the interface package, and then manually synchronize it by copying the new/modified message definitions from [PX4-Autopilot/msg](https://github.com/PX4/PX4-Autopilot/tree/main/msg) to its `msg` folders.
Assuming that PX4-Autopilot is in your home directory `~`, while `px4_msgs` is in `~/ros2_ws/src/`, then the command might be:
Generally this means that you would update [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), clone the interface package, and then manually synchronize it by copying the new/modified message definitions from [PX4-Autopilot/msg](https://github.com/PX4/PX4-Autopilot/tree/main/msg) to its `msg` folders.
Assuming that PX4-Autopilot is in your home directory `~`, while `px4_msgs` is in `~/ros2_ws/src/`, then the command might be:
```sh
rm ~/ros2_ws/src/px4_msgs/msg/*.msg
cp ~/PX4-Autopilot/mgs/*.msg ~/ros2_ws/src/px4_msgs/msg/
```
```sh
rm ~/ros2_ws/src/px4_msgs/msg/*.msg
cp ~/PX4-Autopilot/mgs/*.msg ~/ros2_ws/src/px4_msgs/msg/
```
::: info
Technically, [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) completely defines the relationship between PX4 uORB topics and ROS 2 messages.
For more information see [uXRCE-DDS > DDS Topics YAML](../middleware/uxrce_dds.md#dds-topics-yaml).
::: info
Technically, [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) completely defines the relationship between PX4 uORB topics and ROS 2 messages.
For more information see [uXRCE-DDS > DDS Topics YAML](../middleware/uxrce_dds.md#dds-topics-yaml).
:::
@@ -739,11 +739,11 @@ Note that all the messages from PX4 source code are present in the repository, b
Custom topic and service namespaces can be applied at build time (changing [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml)) or at runtime (useful for multi vehicle operations):
- One possibility is to use the `-n` option when starting the [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) from command line.
Ця техніка може бути використана як у симуляторах, так і на реальних транспортних засобах.
Ця техніка може бути використана як у симуляторах, так і на реальних транспортних засобах.
- A custom namespace can be provided for simulations (only) by setting the environment variable `PX4_UXRCE_DDS_NS` before starting the simulation.
:::info
Changing the namespace at runtime will append the desired namespace as a prefix to all `topic` fields in [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) and all [service servers](#px4-ros-2-service-servers).
Changing the namespace at runtime will append the desired namespace as a prefix to all `topic` fields in [dds_topics.yaml](../middleware/dds_topics.md) and all [service servers](#px4-ros-2-service-servers).
Отже, команди, подібні до:
```sh
@@ -780,7 +780,7 @@ The service servers that are built into the PX4 [uxrce_dds_client](../modules/mo
- `/fmu/vehicle_command` (definition: [`px4_msgs::srv::VehicleCommand`](https://github.com/PX4/px4_msgs/blob/main/srv/VehicleCommand.srv).)
This service can be called by ROS 2 applications to send PX4 [VehicleCommand](../msg_docs/VehicleCommand.md) uORB messages and receive PX4 [VehicleCommandAck](../msg_docs/VehicleCommandAck.md) uORB messages in response.
This service can be called by ROS 2 applications to send PX4 [VehicleCommand](../msg_docs/VehicleCommand.md) uORB messages and receive PX4 [VehicleCommandAck](../msg_docs/VehicleCommandAck.md) uORB messages in response.
All PX4 service names follow the convention `{extra_namespace}/fmu/{server_specific_name}` where `{extra_namespace}` is the same [custom namespace](#customizing-the-namespace) that can be given to the PX4 topics.
@@ -973,36 +973,36 @@ For information about launch files see [ROS 2 Tutorials > Creating launch files]
Якщо щось відсутнє, його можна додати окремо:
- **`colcon`** build tools should be in the development tools.
Можна встановити за допомогою:
Можна встановити за допомогою:
```sh
sudo apt install python3-colcon-common-extensions
```
```sh
sudo apt install python3-colcon-common-extensions
```
- Бібліотеку Eigen3, яку використовує бібліотека трансформацій, повинно бути в обох пакунків: desktop та base.
Воно повинно бути встановлено, як показано:
Воно повинно бути встановлено, як показано:
:::: tabs
:::: tabs
::: tab humble
::: tab humble
```sh
sudo apt install ros-humble-eigen3-cmake-module
```
```sh
sudo apt install ros-humble-eigen3-cmake-module
```
:::
::: tab foxy
::: tab foxy
```sh
sudo apt install ros-foxy-eigen3-cmake-module
```
```sh
sudo apt install ros-foxy-eigen3-cmake-module
```
:::
::::
::::
### ros_gz_bridge not publishing on the \clock topic
+1
View File
@@ -733,6 +733,7 @@
- [Protocols/Microservices](mavlink/protocols.md)
- [Standard Modes Protocol](mavlink/standard_modes.md)
- [uXRCE-DDS (PX4-ROS 2/DDS Bridge)](middleware/uxrce_dds.md)
- [UORB Bridged to ROS 2](middleware/dds_topics.md)
- [模块 & 命令](modules/modules_main.md)
- [自动调参](modules/modules_autotune.md)
- [命令](modules/modules_command.md)
+19 -8
View File
@@ -460,6 +460,7 @@
- [Vehicles](/sim_gazebo_gz/vehicles.md)
- [Advanced Lift Drag Tool](/sim_gazebo_gz/tools_avl_automation.md)
- [Worlds](/sim_gazebo_gz/worlds.md)
- [Plugins](/sim_gazebo_gz/plugins.md)
- [Gazebo Models Repository](/sim_gazebo_gz/gazebo_models.md)
- [Multi-Vehicle Sim](/sim_gazebo_gz/multi_vehicle_simulation.md)
- [Gazebo Classic Simulation](/sim_gazebo_classic/index.md)
@@ -492,12 +493,17 @@
- [Versioned](/msg_docs/versioned_messages.md)
- [ActuatorMotors](/msg_docs/ActuatorMotors.md)
- [ActuatorServos](/msg_docs/ActuatorServos.md)
- [AirspeedValidated](/msg_docs/AirspeedValidated.md)
- [ArmingCheckReply](/msg_docs/ArmingCheckReply.md)
- [ArmingCheckRequest](/msg_docs/ArmingCheckRequest.md)
- [BatteryStatus](/msg_docs/BatteryStatus.md)
- [ConfigOverrides](/msg_docs/ConfigOverrides.md)
- [FixedWingLateralSetpoint](/msg_docs/FixedWingLateralSetpoint.md)
- [FixedWingLongitudinalSetpoint](/msg_docs/FixedWingLongitudinalSetpoint.md)
- [GotoSetpoint](/msg_docs/GotoSetpoint.md)
- [HomePosition](/msg_docs/HomePosition.md)
- [LateralControlConfiguration](/msg_docs/LateralControlConfiguration.md)
- [LongitudinalControlConfiguration](/msg_docs/LongitudinalControlConfiguration.md)
- [ManualControlSetpoint](/msg_docs/ManualControlSetpoint.md)
- [ModeCompleted](/msg_docs/ModeCompleted.md)
- [RegisterExtComponentReply](/msg_docs/RegisterExtComponentReply.md)
@@ -526,10 +532,8 @@
- [ActuatorTest](/msg_docs/ActuatorTest.md)
- [AdcReport](/msg_docs/AdcReport.md)
- [Airspeed](/msg_docs/Airspeed.md)
- [AirspeedValidated](/msg_docs/AirspeedValidated.md)
- [AirspeedWind](/msg_docs/AirspeedWind.md)
- [AutotuneAttitudeControlStatus](/msg_docs/AutotuneAttitudeControlStatus.md)
- [Buffer128](/msg_docs/Buffer128.md)
- [ButtonEvent](/msg_docs/ButtonEvent.md)
- [CameraCapture](/msg_docs/CameraCapture.md)
- [CameraStatus](/msg_docs/CameraStatus.md)
@@ -568,6 +572,9 @@
- [FailsafeFlags](/msg_docs/FailsafeFlags.md)
- [FailureDetectorStatus](/msg_docs/FailureDetectorStatus.md)
- [FigureEightStatus](/msg_docs/FigureEightStatus.md)
- [FixedWingLateralGuidanceStatus](/msg_docs/FixedWingLateralGuidanceStatus.md)
- [FixedWingLateralStatus](/msg_docs/FixedWingLateralStatus.md)
- [FixedWingRunwayControl](/msg_docs/FixedWingRunwayControl.md)
- [FlightPhaseEstimation](/msg_docs/FlightPhaseEstimation.md)
- [FollowTarget](/msg_docs/FollowTarget.md)
- [FollowTargetEstimator](/msg_docs/FollowTargetEstimator.md)
@@ -620,7 +627,6 @@
- [NavigatorMissionItem](/msg_docs/NavigatorMissionItem.md)
- [NavigatorStatus](/msg_docs/NavigatorStatus.md)
- [NormalizedUnsignedSetpoint](/msg_docs/NormalizedUnsignedSetpoint.md)
- [NpfgStatus](/msg_docs/NpfgStatus.md)
- [ObstacleDistance](/msg_docs/ObstacleDistance.md)
- [OffboardControlMode](/msg_docs/OffboardControlMode.md)
- [OnboardComputerStatus](/msg_docs/OnboardComputerStatus.md)
@@ -656,13 +662,12 @@
- [RcParameterMap](/msg_docs/RcParameterMap.md)
- [RoverAttitudeSetpoint](/msg_docs/RoverAttitudeSetpoint.md)
- [RoverAttitudeStatus](/msg_docs/RoverAttitudeStatus.md)
- [RoverMecanumGuidanceStatus](/msg_docs/RoverMecanumGuidanceStatus.md)
- [RoverMecanumSetpoint](/msg_docs/RoverMecanumSetpoint.md)
- [RoverMecanumStatus](/msg_docs/RoverMecanumStatus.md)
- [RoverPositionSetpoint](/msg_docs/RoverPositionSetpoint.md)
- [RoverRateSetpoint](/msg_docs/RoverRateSetpoint.md)
- [RoverRateStatus](/msg_docs/RoverRateStatus.md)
- [RoverSteeringSetpoint](/msg_docs/RoverSteeringSetpoint.md)
- [RoverThrottleSetpoint](/msg_docs/RoverThrottleSetpoint.md)
- [RoverVelocitySetpoint](/msg_docs/RoverVelocitySetpoint.md)
- [RoverVelocityStatus](/msg_docs/RoverVelocityStatus.md)
- [Rpm](/msg_docs/Rpm.md)
- [RtlStatus](/msg_docs/RtlStatus.md)
@@ -694,6 +699,7 @@
- [TelemetryStatus](/msg_docs/TelemetryStatus.md)
- [TiltrotorExtraControls](/msg_docs/TiltrotorExtraControls.md)
- [TimesyncStatus](/msg_docs/TimesyncStatus.md)
- [TrajectorySetpoint6dof](/msg_docs/TrajectorySetpoint6dof.md)
- [TransponderReport](/msg_docs/TransponderReport.md)
- [TuneControl](/msg_docs/TuneControl.md)
- [UavcanParameterRequest](/msg_docs/UavcanParameterRequest.md)
@@ -717,13 +723,16 @@
- [WheelEncoders](/msg_docs/WheelEncoders.md)
- [Wind](/msg_docs/Wind.md)
- [YawEstimatorStatus](/msg_docs/YawEstimatorStatus.md)
- [AirspeedValidatedV0](/msg_docs/AirspeedValidatedV0.md)
- [VehicleAttitudeSetpointV0](/msg_docs/VehicleAttitudeSetpointV0.md)
- [VehicleStatusV0](/msg_docs/VehicleStatusV0.md)
- [MAVLink通讯](/middleware/mavlink.md)
- [MAVLink Messaging](/mavlink/index.md)
- [Adding Messages](/mavlink/adding_messages.md)
- [Streaming Messages](/mavlink/streaming_messages.md)
- [Receiving Messages](/mavlink/receiving_messages.md)
- [Custom MAVLink Messages](/mavlink/custom_messages.md)
- [Standard Modes Protocol](/mavlink/standard_modes.md)
- [Protocols/Microservices](/mavlink/protocols.md)
- [Standard Modes Protocol](/mavlink/standard_modes.md)
- [uXRCE-DDS (PX4-ROS 2/DDS Bridge)](/middleware/uxrce_dds.md)
- [模块 & 命令](/modules/modules_main.md)
- [自动调参](/modules/modules_autotune.md)
@@ -740,6 +749,7 @@
- [磁罗盘](/modules/modules_driver_magnetometer.md)
- [光流](/modules/modules_driver_optical_flow.md)
- [Rpm Sensor](/modules/modules_driver_rpm_sensor.md)
- [Radio Control](/modules/modules_driver_radio_control.md)
- [Transponder](/modules/modules_driver_transponder.md)
- [估计器](/modules/modules_estimator.md)
- [仿真](/modules/modules_simulation.md)
@@ -852,6 +862,7 @@
- [版本发布](/releases/index.md)
- [main (alpha)](/releases/main.md)
- [1.16 (release candidate)](/releases/1.16.md)
- [1.15 (stable)](/releases/1.15.md)
- [1.14](/releases/1.14.md)
- [1.13](/releases/1.13.md)
+58 -58
View File
@@ -47,7 +47,7 @@ PX4 v1.14 (and later) supports the [LightWare LiDAR SF45](../sensor/sf45_rotatin
- Attach and configure the distance sensor on a particular port (see [sensor-specific docs](../sensor/rangefinders.md)) and enable collision prevention using [CP_DIST](#CP_DIST).
- 修改驱动程序以设置方向。
This should be done by mimicking the `SENS_CM8JL65_R_0` parameter (though you might also hard-code the orientation in the sensor _module.yaml_ file to something like `sf0x start -d ${SERIAL_DEV} -R 25` - where 25 is equivalent to `ROTATION_DOWNWARD_FACING`).
This should be done by mimicking the `SENS_CM8JL65_R_0` parameter (though you might also hard-code the orientation in the sensor _module.yaml_ file to something like `sf0x start -d ${SERIAL_DEV} -R 25` - where 25 is equivalent to `ROTATION_DOWNWARD_FACING`).
- Modify the driver to set the _field of view_ in the distance sensor UORB topic (`distance_sensor_s.h_fov`).
## PX4 (Software) Setup
@@ -203,85 +203,85 @@ The Lua script works by extracting the `obstacle_distance_fused` data at each ti
2. Configure PX4 to publish obstacle distance data (so that it is available to PlotJuggler):
Add the [`obstacle_distance_fused`](../msg_docs/ObstacleDistance.md) UORB topic to your [`dds_topics.yaml`](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) so that it is published by PX4:
Add the [`obstacle_distance_fused`](../msg_docs/ObstacleDistance.md) UORB topic to your [`dds_topics.yaml`](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) so that it is published by PX4:
```sh
- topic: /fmu/out/obstacle_distance_fused
type: px4_msgs::msg::ObstacleDistance
```
```sh
- topic: /fmu/out/obstacle_distance_fused
type: px4_msgs::msg::ObstacleDistance
```
For more information see [DDS Topics YAML](../middleware/uxrce_dds.md#dds-topics-yaml) in _uXRCE-DDS (PX4-ROS 2/DDS Bridge)_.
For more information see [DDS Topics YAML](../middleware/uxrce_dds.md#dds-topics-yaml) in [uXRCE-DDS](../middleware/uxrce_dds.md) (PX4-ROS 2/DDS Bridge)_.
3. Open PlotJuggler and navigate to the **Tools > Reactive Script Editor** section.
In the **Script Editor** tab, add following scripts in the appropriate sections:
In the **Script Editor** tab, add following scripts in the appropriate sections:
- **Global code, executed once:**
- **Global code, executed once:**
```lua
obs_dist_fused_xy = ScatterXY.new("obstacle_distance_fused_xy")
obs_dist_min = Timeseries.new("obstacle_distance_minimum")
```
```lua
obs_dist_fused_xy = ScatterXY.new("obstacle_distance_fused_xy")
obs_dist_min = Timeseries.new("obstacle_distance_minimum")
```
- **function(tracker_time)**
- **function(tracker_time)**
```lua
obs_dist_fused_xy:clear()
```lua
obs_dist_fused_xy:clear()
i = 0
angle_offset = TimeseriesView.find("/fmu/out/obstacle_distance_fused/angle_offset")
increment = TimeseriesView.find("/fmu/out/obstacle_distance_fused/increment")
min_dist = 65535
i = 0
angle_offset = TimeseriesView.find("/fmu/out/obstacle_distance_fused/angle_offset")
increment = TimeseriesView.find("/fmu/out/obstacle_distance_fused/increment")
min_dist = 65535
-- Cache increment and angle_offset values at tracker_time to avoid repeated calls
local angle_offset_value = angle_offset:atTime(tracker_time)
local increment_value = increment:atTime(tracker_time)
-- Cache increment and angle_offset values at tracker_time to avoid repeated calls
local angle_offset_value = angle_offset:atTime(tracker_time)
local increment_value = increment:atTime(tracker_time)
if increment_value == nil or increment_value <= 0 then
print("Invalid increment value: " .. tostring(increment_value))
return
end
if increment_value == nil or increment_value <= 0 then
print("Invalid increment value: " .. tostring(increment_value))
return
end
local max_steps = math.floor(360 / increment_value)
local max_steps = math.floor(360 / increment_value)
while i < max_steps do
local str = string.format("/fmu/out/obstacle_distance_fused/distances[%d]", i)
local distance = TimeseriesView.find(str)
if distance == nil then
print("No distance data for: " .. str)
break
end
while i < max_steps do
local str = string.format("/fmu/out/obstacle_distance_fused/distances[%d]", i)
local distance = TimeseriesView.find(str)
if distance == nil then
print("No distance data for: " .. str)
break
end
local dist = distance:atTime(tracker_time)
if dist ~= nil and dist < 65535 then
-- Calculate angle and Cartesian coordinates
local angle = angle_offset_value + i * increment_value
local y = dist * math.cos(math.rad(angle))
local x = dist * math.sin(math.rad(angle))
local dist = distance:atTime(tracker_time)
if dist ~= nil and dist < 65535 then
-- Calculate angle and Cartesian coordinates
local angle = angle_offset_value + i * increment_value
local y = dist * math.cos(math.rad(angle))
local x = dist * math.sin(math.rad(angle))
obs_dist_fused_xy:push_back(x, y)
obs_dist_fused_xy:push_back(x, y)
-- Update minimum distance
if dist < min_dist then
min_dist = dist
end
end
-- Update minimum distance
if dist < min_dist then
min_dist = dist
end
end
i = i + 1
end
i = i + 1
end
-- Push minimum distance once after the loop
if min_dist < 65535 then
obs_dist_min:push_back(tracker_time, min_dist)
else
print("No valid minimum distance found")
end
```
-- Push minimum distance once after the loop
if min_dist < 65535 then
obs_dist_min:push_back(tracker_time, min_dist)
else
print("No valid minimum distance found")
end
```
4. Enter a name for the script on the top right, and press **Save**.
Once saved, the script should appear in the _Active Scripts_ section.
Once saved, the script should appear in the _Active Scripts_ section.
5. Start streaming the data using the approach described in [Plotting uORB Topic Data in Real Time using PlotJuggler](../debug/plotting_realtime_uorb_data.md).
You should see the `obstacle_distance_fused_xy` and `obstacle_distance_minimum` timeseries on the left.
You should see the `obstacle_distance_fused_xy` and `obstacle_distance_minimum` timeseries on the left.
Note that you have to press **Save** again to re-enable the scripts after loading a new log file or otherwise clearing data.
+3 -3
View File
@@ -96,13 +96,13 @@ Exporting the messages allows ROS 2 and the uXRCE-DDS agent to be independent of
While `px4_msgs` has messages for all uORB topics in PX4, not all messages in `px4_msgs` are available to ROS 2/PlotJuggler by default.
The set that are available must be built into the client running on PX4.
These are defined in [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml).
These are defined in [dds_topics.yaml](../middleware/dds_topics.md).
The instructions below explain the changes needed to monitor topics that are not available by default.
### Missing Topics
If a normal uORB topic is not available in PlotJuggler you will need to modify the [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) to include the topic and rebuild PX4.
If a normal uORB topic is not available in PlotJuggler you will need to modify the [dds_topics.yaml](../middleware/dds_topics.md) ([source](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml)) to include the topic and rebuild PX4.
If working with real hardware you will need to build and [install](../config/firmware.md#installing-px4-main-beta-or-custom-firmware) custom firmware after changing the YAML file.
@@ -122,7 +122,7 @@ cd ~/ros2_ws/ && colcon build
### Custom Topics
After defining the topic, follow the instructions above to add the topic to [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), and export the new message into your ROS 2 workspace.
After defining the topic, follow the instructions above to add the topic to [dds_topics.yaml](../middleware/dds_topics.md), and export the new message into your ROS 2 workspace.
## See also
+1 -2
View File
@@ -128,8 +128,7 @@ In EKF2 mode, the replay will automatically create the ORB publisher rules descr
To perform an EKF2 replay:
- Record the original log.
Optionally set `SDLOG_MODE` to `1` to log from boot.
- Record the original log with `SDLOG_MODE` set to `1` to log from boot.
- In addition to the `replay` environment variable, set `replay_mode` to `ekf2`:
+277
View File
@@ -0,0 +1,277 @@
# dds_topics.yaml — PX4 Topics Exposed to ROS 2
:::info
This document is [auto-generated](https://github.com/PX4/PX4-Autopilot/blob/main/Tools/msg/generate_msg_docs.py) from the source code.
:::
The [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) file specifies which uORB message definitions are compiled into the [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) module when [PX4 is built](../middleware/uxrce_dds.md#code-generation), and hence which topics are available for ROS 2 applications to subscribe or publish (by default).
This document shows a markdown-rendered version of [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), listing the publications, subscriptions, and so on.
## Publications
| Topic | 类型 | Rate Limit |
| --------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -------------------- |
| `/fmu/out/register_ext_component_reply` | [px4_msgs::msg::RegisterExtComponentReply](../msg_docs/RegisterExtComponentReply.md) | |
| `/fmu/out/arming_check_request` | [px4_msgs::msg::ArmingCheckRequest](../msg_docs/ArmingCheckRequest.md) | 5.0 |
| `/fmu/out/mode_completed` | [px4_msgs::msg::ModeCompleted](../msg_docs/ModeCompleted.md) | 50.0 |
| `/fmu/out/battery_status` | [px4_msgs::msg::BatteryStatus](../msg_docs/BatteryStatus.md) | 1.0 |
| `/fmu/out/collision_constraints` | [px4_msgs::msg::CollisionConstraints](../msg_docs/CollisionConstraints.md) | 50.0 |
| `/fmu/out/estimator_status_flags` | [px4_msgs::msg::EstimatorStatusFlags](../msg_docs/EstimatorStatusFlags.md) | 5.0 |
| `/fmu/out/failsafe_flags` | [px4_msgs::msg::FailsafeFlags](../msg_docs/FailsafeFlags.md) | 5.0 |
| `/fmu/out/manual_control_setpoint` | [px4_msgs::msg::ManualControlSetpoint](../msg_docs/ManualControlSetpoint.md) | 25.0 |
| `/fmu/out/message_format_response` | [px4_msgs::msg::MessageFormatResponse](../msg_docs/MessageFormatResponse.md) | |
| `/fmu/out/position_setpoint_triplet` | [px4_msgs::msg::PositionSetpointTriplet](../msg_docs/PositionSetpointTriplet.md) | 5.0 |
| `/fmu/out/sensor_combined` | [px4_msgs::msg::SensorCombined](../msg_docs/SensorCombined.md) | |
| `/fmu/out/timesync_status` | [px4_msgs::msg::TimesyncStatus](../msg_docs/TimesyncStatus.md) | 10.0 |
| `/fmu/out/vehicle_land_detected` | [px4_msgs::msg::VehicleLandDetected](../msg_docs/VehicleLandDetected.md) | 5.0 |
| `/fmu/out/vehicle_attitude` | [px4_msgs::msg::VehicleAttitude](../msg_docs/VehicleAttitude.md) | |
| `/fmu/out/vehicle_control_mode` | [px4_msgs::msg::VehicleControlMode](../msg_docs/VehicleControlMode.md) | 50.0 |
| `/fmu/out/vehicle_command_ack` | [px4_msgs::msg::VehicleCommandAck](../msg_docs/VehicleCommandAck.md) | |
| `/fmu/out/vehicle_global_position` | [px4_msgs::msg::VehicleGlobalPosition](../msg_docs/VehicleGlobalPosition.md) | 50.0 |
| `/fmu/out/vehicle_gps_position` | [px4_msgs::msg::SensorGps](../msg_docs/SensorGps.md) | 50.0 |
| `/fmu/out/vehicle_local_position` | [px4_msgs::msg::VehicleLocalPosition](../msg_docs/VehicleLocalPosition.md) | 50.0 |
| `/fmu/out/vehicle_odometry` | [px4_msgs::msg::VehicleOdometry](../msg_docs/VehicleOdometry.md) | |
| `/fmu/out/vehicle_status` | [px4_msgs::msg::VehicleStatus](../msg_docs/VehicleStatus.md) | 5.0 |
| `/fmu/out/airspeed_validated` | [px4_msgs::msg::AirspeedValidated](../msg_docs/AirspeedValidated.md) | 50.0 |
| `/fmu/out/vtol_vehicle_status` | [px4_msgs::msg::VtolVehicleStatus](../msg_docs/VtolVehicleStatus.md) | |
| `/fmu/out/home_position` | [px4_msgs::msg::HomePosition](../msg_docs/HomePosition.md) | 5.0 |
## Subscriptions
| Topic | 类型 |
| ------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| /fmu/in/register_ext_component_request | [px4_msgs::msg::RegisterExtComponentRequest](../msg_docs/RegisterExtComponentRequest.md) |
| /fmu/in/unregister_ext_component | [px4_msgs::msg::UnregisterExtComponent](../msg_docs/UnregisterExtComponent.md) |
| /fmu/in/config_overrides_request | [px4_msgs::msg::ConfigOverrides](../msg_docs/ConfigOverrides.md) |
| /fmu/in/arming_check_reply | [px4_msgs::msg::ArmingCheckReply](../msg_docs/ArmingCheckReply.md) |
| /fmu/in/message_format_request | [px4_msgs::msg::MessageFormatRequest](../msg_docs/MessageFormatRequest.md) |
| /fmu/in/mode_completed | [px4_msgs::msg::ModeCompleted](../msg_docs/ModeCompleted.md) |
| /fmu/in/config_control_setpoints | [px4_msgs::msg::VehicleControlMode](../msg_docs/VehicleControlMode.md) |
| /fmu/in/distance_sensor | [px4_msgs::msg::DistanceSensor](../msg_docs/DistanceSensor.md) |
| /fmu/in/manual_control_input | [px4_msgs::msg::ManualControlSetpoint](../msg_docs/ManualControlSetpoint.md) |
| /fmu/in/offboard_control_mode | [px4_msgs::msg::OffboardControlMode](../msg_docs/OffboardControlMode.md) |
| /fmu/in/onboard_computer_status | [px4_msgs::msg::OnboardComputerStatus](../msg_docs/OnboardComputerStatus.md) |
| /fmu/in/obstacle_distance | [px4_msgs::msg::ObstacleDistance](../msg_docs/ObstacleDistance.md) |
| /fmu/in/sensor_optical_flow | [px4_msgs::msg::SensorOpticalFlow](../msg_docs/SensorOpticalFlow.md) |
| /fmu/in/goto_setpoint | [px4_msgs::msg::GotoSetpoint](../msg_docs/GotoSetpoint.md) |
| /fmu/in/telemetry_status | [px4_msgs::msg::TelemetryStatus](../msg_docs/TelemetryStatus.md) |
| /fmu/in/trajectory_setpoint | [px4_msgs::msg::TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) |
| /fmu/in/vehicle_attitude_setpoint | [px4_msgs::msg::VehicleAttitudeSetpoint](../msg_docs/VehicleAttitudeSetpoint.md) |
| /fmu/in/vehicle_mocap_odometry | [px4_msgs::msg::VehicleOdometry](../msg_docs/VehicleOdometry.md) |
| /fmu/in/vehicle_rates_setpoint | [px4_msgs::msg::VehicleRatesSetpoint](../msg_docs/VehicleRatesSetpoint.md) |
| /fmu/in/vehicle_visual_odometry | [px4_msgs::msg::VehicleOdometry](../msg_docs/VehicleOdometry.md) |
| /fmu/in/vehicle_command | [px4_msgs::msg::VehicleCommand](../msg_docs/VehicleCommand.md) |
| /fmu/in/vehicle_command_mode_executor | [px4_msgs::msg::VehicleCommand](../msg_docs/VehicleCommand.md) |
| /fmu/in/vehicle_thrust_setpoint | [px4_msgs::msg::VehicleThrustSetpoint](../msg_docs/VehicleThrustSetpoint.md) |
| /fmu/in/vehicle_torque_setpoint | [px4_msgs::msg::VehicleTorqueSetpoint](../msg_docs/VehicleTorqueSetpoint.md) |
| /fmu/in/actuator_motors | [px4_msgs::msg::ActuatorMotors](../msg_docs/ActuatorMotors.md) |
| /fmu/in/actuator_servos | [px4_msgs::msg::ActuatorServos](../msg_docs/ActuatorServos.md) |
| /fmu/in/aux_global_position | [px4_msgs::msg::VehicleGlobalPosition](../msg_docs/VehicleGlobalPosition.md) |
| /fmu/in/fixed_wing_longitudinal_setpoint | [px4_msgs::msg::FixedWingLongitudinalSetpoint](../msg_docs/FixedWingLongitudinalSetpoint.md) |
| /fmu/in/fixed_wing_lateral_setpoint | [px4_msgs::msg::FixedWingLateralSetpoint](../msg_docs/FixedWingLateralSetpoint.md) |
| /fmu/in/longitudinal_control_configuration | [px4_msgs::msg::LongitudinalControlConfiguration](../msg_docs/LongitudinalControlConfiguration.md) |
| /fmu/in/lateral_control_configuration | [px4_msgs::msg::LateralControlConfiguration](../msg_docs/LateralControlConfiguration.md) |
## Subscriptions Multi
None
## Not Exported
These messages are not listed in the yaml file.
They are not build into the module, and hence are neither published or subscribed.
:::details
See messages
- [SensorCorrection](../msg_docs/SensorCorrection.md)
- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md)
- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md)
- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md)
- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md)
- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md)
- [Px4ioStatus](../msg_docs/Px4ioStatus.md)
- [SatelliteInfo](../msg_docs/SatelliteInfo.md)
- [GeofenceResult](../msg_docs/GeofenceResult.md)
- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md)
- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md)
- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md)
- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md)
- [EventV0](../msg_docs/EventV0.md)
- [QshellRetval](../msg_docs/QshellRetval.md)
- [RoverThrottleSetpoint](../msg_docs/RoverThrottleSetpoint.md)
- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md)
- [RcChannels](../msg_docs/RcChannels.md)
- [SensorAccel](../msg_docs/SensorAccel.md)
- [GimbalDeviceAttitudeStatus](../msg_docs/GimbalDeviceAttitudeStatus.md)
- [EscStatus](../msg_docs/EscStatus.md)
- [RoverAttitudeSetpoint](../msg_docs/RoverAttitudeSetpoint.md)
- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md)
- [AirspeedWind](../msg_docs/AirspeedWind.md)
- [InputRc](../msg_docs/InputRc.md)
- [GpioIn](../msg_docs/GpioIn.md)
- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md)
- [VehicleImu](../msg_docs/VehicleImu.md)
- [Event](../msg_docs/Event.md)
- [SensorUwb](../msg_docs/SensorUwb.md)
- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md)
- [DatamanResponse](../msg_docs/DatamanResponse.md)
- [OrbTest](../msg_docs/OrbTest.md)
- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md)
- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md)
- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md)
- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md)
- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md)
- [TakeoffStatus](../msg_docs/TakeoffStatus.md)
- [UlogStreamAck](../msg_docs/UlogStreamAck.md)
- [OrbTestLarge](../msg_docs/OrbTestLarge.md)
- [RoverSteeringSetpoint](../msg_docs/RoverSteeringSetpoint.md)
- [CameraCapture](../msg_docs/CameraCapture.md)
- [VehicleRoi](../msg_docs/VehicleRoi.md)
- [ActuatorArmed](../msg_docs/ActuatorArmed.md)
- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md)
- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md)
- [GeofenceStatus](../msg_docs/GeofenceStatus.md)
- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md)
- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md)
- [PowerMonitor](../msg_docs/PowerMonitor.md)
- [RoverVelocityStatus](../msg_docs/RoverVelocityStatus.md)
- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md)
- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md)
- [TecsStatus](../msg_docs/TecsStatus.md)
- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md)
- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md)
- [Ping](../msg_docs/Ping.md)
- [LedControl](../msg_docs/LedControl.md)
- [Wind](../msg_docs/Wind.md)
- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md)
- [ActuatorTest](../msg_docs/ActuatorTest.md)
- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md)
- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md)
- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md)
- [Gripper](../msg_docs/Gripper.md)
- [SensorMag](../msg_docs/SensorMag.md)
- [DebugValue](../msg_docs/DebugValue.md)
- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md)
- [RcParameterMap](../msg_docs/RcParameterMap.md)
- [LandingGear](../msg_docs/LandingGear.md)
- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md)
- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md)
- [UlogStream](../msg_docs/UlogStream.md)
- [GimbalControls](../msg_docs/GimbalControls.md)
- [RoverRateSetpoint](../msg_docs/RoverRateSetpoint.md)
- [LogMessage](../msg_docs/LogMessage.md)
- [RoverVelocitySetpoint](../msg_docs/RoverVelocitySetpoint.md)
- [GpioOut](../msg_docs/GpioOut.md)
- [TaskStackInfo](../msg_docs/TaskStackInfo.md)
- [VelocityLimits](../msg_docs/VelocityLimits.md)
- [MagWorkerData](../msg_docs/MagWorkerData.md)
- [ParameterUpdate](../msg_docs/ParameterUpdate.md)
- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md)
- [SensorBaro](../msg_docs/SensorBaro.md)
- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md)
- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md)
- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md)
- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md)
- [Rpm](../msg_docs/Rpm.md)
- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md)
- [MountOrientation](../msg_docs/MountOrientation.md)
- [ActionRequest](../msg_docs/ActionRequest.md)
- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md)
- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md)
- [LoggerStatus](../msg_docs/LoggerStatus.md)
- [GeneratorStatus](../msg_docs/GeneratorStatus.md)
- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md)
- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md)
- [LandingTargetPose](../msg_docs/LandingTargetPose.md)
- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md)
- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md)
- [OrbitStatus](../msg_docs/OrbitStatus.md)
- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md)
- [EstimatorStatus](../msg_docs/EstimatorStatus.md)
- [DatamanRequest](../msg_docs/DatamanRequest.md)
- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md)
- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md)
- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md)
- [Cpuload](../msg_docs/Cpuload.md)
- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md)
- [RoverRateStatus](../msg_docs/RoverRateStatus.md)
- [EscReport](../msg_docs/EscReport.md)
- [DebugArray](../msg_docs/DebugArray.md)
- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md)
- [SensorHygrometer](../msg_docs/SensorHygrometer.md)
- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md)
- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md)
- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md)
- [QshellReq](../msg_docs/QshellReq.md)
- [CameraStatus](../msg_docs/CameraStatus.md)
- [GpsInjectData](../msg_docs/GpsInjectData.md)
- [FigureEightStatus](../msg_docs/FigureEightStatus.md)
- [TransponderReport](../msg_docs/TransponderReport.md)
- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md)
- [MavlinkLog](../msg_docs/MavlinkLog.md)
- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md)
- [FuelTankStatus](../msg_docs/FuelTankStatus.md)
- [Mission](../msg_docs/Mission.md)
- [PositionSetpoint](../msg_docs/PositionSetpoint.md)
- [MissionResult](../msg_docs/MissionResult.md)
- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md)
- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md)
- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md)
- [DifferentialPressure](../msg_docs/DifferentialPressure.md)
- [CellularStatus](../msg_docs/CellularStatus.md)
- [GpsDump](../msg_docs/GpsDump.md)
- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md)
- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md)
- [NavigatorStatus](../msg_docs/NavigatorStatus.md)
- [RoverPositionSetpoint](../msg_docs/RoverPositionSetpoint.md)
- [FollowTarget](../msg_docs/FollowTarget.md)
- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md)
- [EstimatorStates](../msg_docs/EstimatorStates.md)
- [SensorGyro](../msg_docs/SensorGyro.md)
- [SensorAirflow](../msg_docs/SensorAirflow.md)
- [ButtonEvent](../msg_docs/ButtonEvent.md)
- [DebugKeyValue](../msg_docs/DebugKeyValue.md)
- [GpioConfig](../msg_docs/GpioConfig.md)
- [CameraTrigger](../msg_docs/CameraTrigger.md)
- [LandingGearWheel](../msg_docs/LandingGearWheel.md)
- [VehicleConstraints](../msg_docs/VehicleConstraints.md)
- [HealthReport](../msg_docs/HealthReport.md)
- [PowerButtonState](../msg_docs/PowerButtonState.md)
- [RadioStatus](../msg_docs/RadioStatus.md)
- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md)
- [EstimatorBias](../msg_docs/EstimatorBias.md)
- [DebugVect](../msg_docs/DebugVect.md)
- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md)
- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md)
- [PpsCapture](../msg_docs/PpsCapture.md)
- [SensorSelection](../msg_docs/SensorSelection.md)
- [SystemPower](../msg_docs/SystemPower.md)
- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md)
- [SensorGyroFft](../msg_docs/SensorGyroFft.md)
- [VehicleAirData](../msg_docs/VehicleAirData.md)
- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md)
- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md)
- [GpioRequest](../msg_docs/GpioRequest.md)
- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md)
- [RtlStatus](../msg_docs/RtlStatus.md)
- [Airspeed](../msg_docs/Airspeed.md)
- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md)
- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md)
- [IrlockReport](../msg_docs/IrlockReport.md)
- [HeaterStatus](../msg_docs/HeaterStatus.md)
- [AdcReport](../msg_docs/AdcReport.md)
- [PwmInput](../msg_docs/PwmInput.md)
- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md)
- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md)
- [OrbTestMedium](../msg_docs/OrbTestMedium.md)
- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md)
- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md)
- [TuneControl](../msg_docs/TuneControl.md)
- [WheelEncoders](../msg_docs/WheelEncoders.md)
- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md)
- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md)
- [SensorsStatus](../msg_docs/SensorsStatus.md)
:::
+24 -5
View File
@@ -61,12 +61,12 @@ For example the [VelocityLimits](../msg_docs/VelocityLimits.md) message definiti
```text
# Velocity and yaw rate limits for a multicopter position slow mode only
uint64 timestamp # time since system start (microseconds)
uint64 timestamp # [us] Time since system start.
# absolute speeds, NAN means use default limit
float32 horizontal_velocity # [m/s]
float32 vertical_velocity # [m/s]
float32 yaw_rate # [rad/s]
float32 horizontal_velocity # [m/s] Horizontal velocity.
float32 vertical_velocity # [m/s] Vertical velocity.
float32 yaw_rate # [rad/s] Yaw rate.
```
By default this message definition will be compiled to a single topic with an id `velocity_limits`, a direct conversion from the CamelCase name to a snake_case version.
@@ -92,15 +92,34 @@ To nest a message, simply include the nested message type in the parent message
```text
# Global position setpoint triplet in WGS84 coordinates.
#
# This are the three next waypoints (or just the next two or one).
uint64 timestamp # time since system start (microseconds)
uint64 timestamp # [us] Time since system start.
PositionSetpoint previous
PositionSetpoint current
PositionSetpoint next
```
### uORB Buffer Length (ORB_QUEUE_LENGTH)
uORB messages have a single-message buffer by default, which may be overwritten if the message publication rate is too high.
In most cases this does not matter: either we are only interested in the latest sample of a topic, such as a sensor value or a setpoint, or losing a few samples is not a particular problem.
For relatively few cases, such as vehicle commands, it is important that we don't drop topics.
In order to reduce the chance that messages will be dropped we can use named constant `ORB_QUEUE_LENGTH` to create a buffer of the specified length.
For example, to create a four-message queue, add the following line to your message definition:
```sh
uint8 ORB_QUEUE_LENGTH = 4
```
As long as subscribers are able to read messages out of the buffer quickly enough than it isn't ever fully filled to the queue length (by publishers), they will be able to get all messages that are sent.
Messages will still be lost they are published when the queue is filled.
Note that the queue length value must be a power of 2 (so 2, 4, 8, ...).
### Message/Field Deprecation {#deprecation}
As there are external tools using uORB messages from log files, such as [Flight Review](https://github.com/PX4/flight_review), certain aspects need to be considered when updating existing messages:
+7 -9
View File
@@ -38,7 +38,7 @@ The PX4 [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) is gen
The agent has no dependency on client code.
It can be built standalone or in a ROS 2 workspace, or installed as a snap package on Ubuntu.
When PX4 is built, a code generator uses the uORB message definitions in the source tree ([PX4-Autopilot/msg](https://github.com/PX4/PX4-Autopilot/tree/main/msg)) to compile support for the subset of uORB topics in [PX4-Autopilot/src/modules/uxrce_dds_client/dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) into [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client).
When PX4 is built, a code generator uses the uORB message definitions in the source tree ([PX4-Autopilot/msg](https://github.com/PX4/PX4-Autopilot/tree/main/msg)) to compile support for the subset of uORB topics in [/src/modules/uxrce_dds_client/dds_topics.yaml](../middleware/dds_topics.md) into [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client).
PX4 main or release builds automatically export the set of uORB messages definitions in the build to an associated branch in [PX4/px4_msgs](https://github.com/PX4/px4_msgs).
@@ -326,13 +326,11 @@ ROS_DOMAIN_ID=3 PX4_UXRCE_DDS_PORT=9999 PX4_UXRCE_DDS_NS=drone make px4_sitl gz_
## Supported uORB Messages
The set of [PX4 uORB topics](../msg_docs/index.md) that are exposed through the client are set in [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml).
The set of [PX4 uORB topics](../msg_docs/index.md) that are exposed through the client are set in [dds_topics.yaml](../middleware/dds_topics.md).
The topics are release specific (support is compiled into [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) at build time).
While most releases should support a very similar set of messages, to be certain you would need to check the yaml file for your particular release.
<!-- Jublish the set we use?: https://github.com/PX4/px4_msgs/issues/22 -->
Note that ROS 2/DDS needs to have the _same_ message definitions that were used to create the uXRCE-DDS client module in the PX4 Firmware in order to interpret the messages.
The message definitions are stored in the ROS 2 interface package [PX4/px4_msgs](https://github.com/PX4/px4_msgs), and they are automatically synchronized by CI on the `main` and release branches.
Note that all the messages from PX4 source code are present in the repository, but only those listed in `dds_topics.yaml` will be available as ROS 2 topics.
@@ -349,21 +347,21 @@ Therefore,
```
::: info
Technically, [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) completely defines the relationship between PX4 uORB topics and ROS 2 messages.
Technically, [dds_topics.yaml](../middleware/dds_topics.md) completely defines the relationship between PX4 uORB topics and ROS 2 messages.
For more information see [DDS Topics YAML](#dds-topics-yaml) below.
:::
## Customizing the Namespace
Custom topic and service namespaces can be applied at build time (changing [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml)) or at runtime (which is useful for multi vehicle operations):
Custom topic and service namespaces can be applied at build time (changing [dds_topics.yaml](../middleware/dds_topics.md)) or at runtime (which is useful for multi vehicle operations):
- One possibility is to use the `-n` option when starting the [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) from command line.
This technique can be used both in simulation and real vehicles.
- A custom namespace can be provided for simulations (only) by setting the environment variable `PX4_UXRCE_DDS_NS` before starting the simulation.
:::info
Changing the namespace at runtime will append the desired namespace as a prefix to all `topic` fields in [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) and all [service servers](#dds-ros-2-services).
Changing the namespace at runtime will append the desired namespace as a prefix to all `topic` fields in [dds_topics.yaml](../middleware/dds_topics.md) and all [service servers](#dds-ros-2-services).
Therefore, commands like:
```sh
@@ -420,7 +418,7 @@ Deadline, lifespan, and lease durations are also all set to "default".
## DDS Topics YAML
The PX4 yaml file [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) defines the set of PX4 uORB topics that are built into firmware and published.
The PX4 [dds_topics.yaml](../middleware/dds_topics.md) file defines the set of PX4 uORB topics that are built into firmware and published.
More precisely, it completely defines the relationship/pairing between PX4 uORB and ROS 2 messages.
The file is structured as follows:
@@ -549,7 +547,7 @@ Take a look at the [client startup section](#starting-the-client) to learn how t
#### New file for setting which topics are published
The list of topics that are published and subscribed for a particular firmware is now managed by the [dds_topic.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) configuration file, which replaces [urtps_bridge_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/release/1.13/msg/tools/urtps_bridge_topics.yaml)
The list of topics that are published and subscribed for a particular firmware is now managed by the [dds_topics.yaml](../middleware/dds_topics.md) configuration file, which replaces [urtps_bridge_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/release/1.13/msg/tools/urtps_bridge_topics.yaml)
See [Supported uORB Messages](#supported-uorb-messages) and [DDS Topics YAML](#dds-topics-yaml) sections for more information.
+138 -138
View File
@@ -28,7 +28,7 @@ The agent acts as a proxy for the client to publish and subscribe to topics in t
The PX4 [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) is generated at build time and included in PX4 firmware by default.
It includes both the "generic" micro XRCE-DDS client code, and PX4-specific translation code that it uses to publish to/from uORB topics.
The subset of uORB messages that are generated into the client are listed in [PX4-Autopilot/src/modules/uxrce_dds_client/dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml).
The subset of uORB messages that are generated into the client are specified in [dds_topics.yaml](../middleware/dds_topics.md).
The generator uses the uORB message definitions in the source tree: [PX4-Autopilot/msg](https://github.com/PX4/PX4-Autopilot/tree/main/msg) to create the code for sending ROS 2 messages.
ROS 2 applications need to be built in a workspace that has the _same_ message definitions that were used to create the uXRCE-DDS client module in the PX4 Firmware.
@@ -97,48 +97,48 @@ To install ROS 2 and its dependencies:
1. Install ROS 2.
:::: tabs
:::: tabs
::: tab humble
To install ROS 2 "Humble" on Ubuntu 22.04:
::: tab humble
To install ROS 2 "Humble" on Ubuntu 22.04:
```sh
sudo apt update && sudo apt install locales
sudo locale-gen en_US en_US.UTF-8
sudo update-locale LC_ALL=en_US.UTF-8 LANG=en_US.UTF-8
export LANG=en_US.UTF-8
sudo apt install software-properties-common
sudo add-apt-repository universe
sudo apt update && sudo apt install curl -y
sudo curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -o /usr/share/keyrings/ros-archive-keyring.gpg
echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/ros-archive-keyring.gpg] http://packages.ros.org/ros2/ubuntu $(. /etc/os-release && echo $UBUNTU_CODENAME) main" | sudo tee /etc/apt/sources.list.d/ros2.list > /dev/null
sudo apt update && sudo apt upgrade -y
sudo apt install ros-humble-desktop
sudo apt install ros-dev-tools
source /opt/ros/humble/setup.bash && echo "source /opt/ros/humble/setup.bash" >> .bashrc
```
```sh
sudo apt update && sudo apt install locales
sudo locale-gen en_US en_US.UTF-8
sudo update-locale LC_ALL=en_US.UTF-8 LANG=en_US.UTF-8
export LANG=en_US.UTF-8
sudo apt install software-properties-common
sudo add-apt-repository universe
sudo apt update && sudo apt install curl -y
sudo curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -o /usr/share/keyrings/ros-archive-keyring.gpg
echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/ros-archive-keyring.gpg] http://packages.ros.org/ros2/ubuntu $(. /etc/os-release && echo $UBUNTU_CODENAME) main" | sudo tee /etc/apt/sources.list.d/ros2.list > /dev/null
sudo apt update && sudo apt upgrade -y
sudo apt install ros-humble-desktop
sudo apt install ros-dev-tools
source /opt/ros/humble/setup.bash && echo "source /opt/ros/humble/setup.bash" >> .bashrc
```
The instructions above are reproduced from the official installation guide: [Install ROS 2 Humble](https://docs.ros.org/en/humble/Installation/Ubuntu-Install-Debians.html).
You can install _either_ the desktop (`ros-humble-desktop`) _or_ bare-bones versions (`ros-humble-ros-base`), _and_ the development tools (`ros-dev-tools`).
The instructions above are reproduced from the official installation guide: [Install ROS 2 Humble](https://docs.ros.org/en/humble/Installation/Ubuntu-Install-Debians.html).
You can install _either_ the desktop (`ros-humble-desktop`) _or_ bare-bones versions (`ros-humble-ros-base`), _and_ the development tools (`ros-dev-tools`).
:::
::: tab foxy
To install ROS 2 "Foxy" on Ubuntu 20.04:
::: tab foxy
To install ROS 2 "Foxy" on Ubuntu 20.04:
- Follow the official installation guide: [Install ROS 2 Foxy](https://docs.ros.org/en/foxy/Installation/Ubuntu-Install-Debians.html).
- Follow the official installation guide: [Install ROS 2 Foxy](https://docs.ros.org/en/foxy/Installation/Ubuntu-Install-Debians.html).
You can install _either_ the desktop (`ros-foxy-desktop`) _or_ bare-bones versions (`ros-foxy-ros-base`), _and_ the development tools (`ros-dev-tools`).
You can install _either_ the desktop (`ros-foxy-desktop`) _or_ bare-bones versions (`ros-foxy-ros-base`), _and_ the development tools (`ros-dev-tools`).
:::
::::
::::
2. Some Python dependencies must also be installed (using **`pip`** or **`apt`**):
```sh
pip install --user -U empy==3.3.4 pyros-genmsg setuptools
```
```sh
pip install --user -U empy==3.3.4 pyros-genmsg setuptools
```
### Setup Micro XRCE-DDS Agent & Client
@@ -155,22 +155,22 @@ To setup and start the agent:
2. 输入以下命令从仓库获取源代码并构建代理(Agent):
```sh
git clone -b v2.4.2 https://github.com/eProsima/Micro-XRCE-DDS-Agent.git
cd Micro-XRCE-DDS-Agent
mkdir build
cd build
cmake ..
make
sudo make install
sudo ldconfig /usr/local/lib/
```
```sh
git clone -b v2.4.2 https://github.com/eProsima/Micro-XRCE-DDS-Agent.git
cd Micro-XRCE-DDS-Agent
mkdir build
cd build
cmake ..
make
sudo make install
sudo ldconfig /usr/local/lib/
```
3. 启动代理并设置以连接运行在模拟器上的 uXRCE-DDS客户端(Client)
```sh
MicroXRCEAgent udp4 -p 8888
```
```sh
MicroXRCEAgent udp4 -p 8888
```
The agent is now running, but you won't see much until we start PX4 (in the next step).
@@ -187,31 +187,31 @@ To start the simulator (and client):
1. Open a new terminal in the root of the **PX4 Autopilot** repo that was installed above.
:::: tabs
:::: tabs
::: tab humble
::: tab humble
- Start a PX4 [Gazebo](../sim_gazebo_gz/index.md) simulation using:
- Start a PX4 [Gazebo](../sim_gazebo_gz/index.md) simulation using:
```sh
make px4_sitl gz_x500
```
```sh
make px4_sitl gz_x500
```
:::
::: tab foxy
::: tab foxy
- Start a PX4 [Gazebo Classic](../sim_gazebo_classic/index.md) simulation using:
- Start a PX4 [Gazebo Classic](../sim_gazebo_classic/index.md) simulation using:
```sh
make px4_sitl gazebo-classic
```
```sh
make px4_sitl gazebo-classic
```
:::
::::
::::
The agent and client are now running they should connect.
@@ -261,52 +261,52 @@ To create and build the workspace:
2. Create and navigate into a new workspace directory using:
```sh
mkdir -p ~/ws_sensor_combined/src/
cd ~/ws_sensor_combined/src/
```
```sh
mkdir -p ~/ws_sensor_combined/src/
cd ~/ws_sensor_combined/src/
```
::: info
A naming convention for workspace folders can make it easier to manage workspaces.
::: info
A naming convention for workspace folders can make it easier to manage workspaces.
:::
3. Clone the example repository and [px4_msgs](https://github.com/PX4/px4_msgs) to the `/src` directory (the `main` branch is cloned by default, which corresponds to the version of PX4 we are running):
```sh
git clone https://github.com/PX4/px4_msgs.git
git clone https://github.com/PX4/px4_ros_com.git
```
```sh
git clone https://github.com/PX4/px4_msgs.git
git clone https://github.com/PX4/px4_ros_com.git
```
4. Source the ROS 2 development environment into the current terminal and compile the workspace using `colcon`:
:::: tabs
:::: tabs
::: tab humble
::: tab humble
```sh
cd ..
source /opt/ros/humble/setup.bash
colcon build
```
```sh
cd ..
source /opt/ros/humble/setup.bash
colcon build
```
:::
::: tab foxy
::: tab foxy
```sh
cd ..
source /opt/ros/foxy/setup.bash
colcon build
```
```sh
cd ..
source /opt/ros/foxy/setup.bash
colcon build
```
:::
::::
::::
This builds all the folders under `/src` using the sourced toolchain.
This builds all the folders under `/src` using the sourced toolchain.
#### Running the Example
@@ -322,42 +322,42 @@ In a new terminal:
1. Navigate into the top level of your workspace directory and source the ROS 2 environment (in this case "Humble"):
:::: tabs
:::: tabs
::: tab humble
::: tab humble
```sh
cd ~/ws_sensor_combined/
source /opt/ros/humble/setup.bash
```
```sh
cd ~/ws_sensor_combined/
source /opt/ros/humble/setup.bash
```
:::
::: tab foxy
::: tab foxy
```sh
cd ~/ws_sensor_combined/
source /opt/ros/foxy/setup.bash
```
```sh
cd ~/ws_sensor_combined/
source /opt/ros/foxy/setup.bash
```
:::
::::
::::
2. Source the `local_setup.bash`.
```sh
source install/local_setup.bash
```
```sh
source install/local_setup.bash
```
3. Now launch the example.
Note here that we use `ros2 launch`, which is described below.
Note here that we use `ros2 launch`, which is described below.
```sh
ros2 launch px4_ros_com sensor_combined_listener.launch.py
```
```sh
ros2 launch px4_ros_com sensor_combined_listener.launch.py
```
If this is working you should see data being printed on the terminal/console where you launched the ROS listener:
@@ -385,18 +385,18 @@ If you were to use incompatible [message versions](../middleware/uorb.md#message
1. Include the [Message Translation Node](../ros2/px4_ros2_msg_translation_node.md) into the example workspace or a separate workspace by running the following script:
```sh
cd /path/to/ros_ws
/path/to/PX4-Autopilot/Tools/copy_to_ros_ws.sh .
```
```sh
cd /path/to/ros_ws
/path/to/PX4-Autopilot/Tools/copy_to_ros_ws.sh .
```
2. Build and run the translation node:
```sh
colcon build
source install/local_setup.bash
ros2 run translation_node translation_node_bin
```
```sh
colcon build
source install/local_setup.bash
ros2 run translation_node translation_node_bin
```
## Controlling a Vehicle
@@ -405,7 +405,7 @@ To control applications, ROS 2 applications:
- subscribe to (listen to) telemetry topics published by PX4
- publish to topics that cause PX4 to perform some action.
The topics that you can use are defined in [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), and you can get more information about their data in the [uORB Message Reference](../msg_docs/index.md).
The topics that you can use are defined in [dds_topics.yaml](../middleware/dds_topics.md), and you can get more information about their data in the [uORB Message Reference](../msg_docs/index.md).
For example, [VehicleGlobalPosition](../msg_docs/VehicleGlobalPosition.md) can be used to get the vehicle global position, while [VehicleCommand](../msg_docs/VehicleCommand.md) can be used to command actions such as takeoff and land.
The [ROS 2 Example applications](#ros-2-example-applications) examples below provide concrete examples of how to use these topics.
@@ -456,13 +456,13 @@ Therefore, ROS 2 nodes that want to interface with PX4 must take care of the fra
- To rotate a vector from ENU to NED two basic rotations must be performed:
- first a pi/2 rotation around the `Z`-axis (up),
- then a pi rotation around the `X`-axis (old East/new North).
- first a pi/2 rotation around the `Z`-axis (up),
- then a pi rotation around the `X`-axis (old East/new North).
- To rotate a vector from NED to ENU two basic rotations must be performed:
- - first a pi/2 rotation around the `Z`-axis (down),
- then a pi rotation around the `X`-axis (old North/new East). Note that the two resulting operations are mathematically equivalent.
- then a pi rotation around the `X`-axis (old North/new East). Note that the two resulting operations are mathematically equivalent.
- To rotate a vector from FLU to FRD a pi rotation around the `X`-axis (front) is sufficient.
@@ -720,17 +720,17 @@ Therefore,
- If you're using a main or release version of PX4 you can get the message definitions by cloning the interface package [PX4/px4_msgs](https://github.com/PX4/px4_msgs) into your workspace.
- If you're creating or modifying uORB messages you must manually update the messages in your workspace from your PX4 source tree.
Generally this means that you would update [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), clone the interface package, and then manually synchronize it by copying the new/modified message definitions from [PX4-Autopilot/msg](https://github.com/PX4/PX4-Autopilot/tree/main/msg) to its `msg` folders.
Assuming that PX4-Autopilot is in your home directory `~`, while `px4_msgs` is in `~/ros2_ws/src/`, then the command might be:
Generally this means that you would update [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), clone the interface package, and then manually synchronize it by copying the new/modified message definitions from [PX4-Autopilot/msg](https://github.com/PX4/PX4-Autopilot/tree/main/msg) to its `msg` folders.
Assuming that PX4-Autopilot is in your home directory `~`, while `px4_msgs` is in `~/ros2_ws/src/`, then the command might be:
```sh
rm ~/ros2_ws/src/px4_msgs/msg/*.msg
cp ~/PX4-Autopilot/mgs/*.msg ~/ros2_ws/src/px4_msgs/msg/
```
```sh
rm ~/ros2_ws/src/px4_msgs/msg/*.msg
cp ~/PX4-Autopilot/mgs/*.msg ~/ros2_ws/src/px4_msgs/msg/
```
::: info
Technically, [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) completely defines the relationship between PX4 uORB topics and ROS 2 messages.
For more information see [uXRCE-DDS > DDS Topics YAML](../middleware/uxrce_dds.md#dds-topics-yaml).
::: info
Technically, [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) completely defines the relationship between PX4 uORB topics and ROS 2 messages.
For more information see [uXRCE-DDS > DDS Topics YAML](../middleware/uxrce_dds.md#dds-topics-yaml).
:::
@@ -739,11 +739,11 @@ Therefore,
Custom topic and service namespaces can be applied at build time (changing [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml)) or at runtime (useful for multi vehicle operations):
- One possibility is to use the `-n` option when starting the [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) from command line.
This technique can be used both in simulation and real vehicles.
This technique can be used both in simulation and real vehicles.
- A custom namespace can be provided for simulations (only) by setting the environment variable `PX4_UXRCE_DDS_NS` before starting the simulation.
:::info
Changing the namespace at runtime will append the desired namespace as a prefix to all `topic` fields in [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) and all [service servers](#px4-ros-2-service-servers).
Changing the namespace at runtime will append the desired namespace as a prefix to all `topic` fields in [dds_topics.yaml](../middleware/dds_topics.md) and all [service servers](#px4-ros-2-service-servers).
Therefore, commands like:
```sh
@@ -780,7 +780,7 @@ The service servers that are built into the PX4 [uxrce_dds_client](../modules/mo
- `/fmu/vehicle_command` (definition: [`px4_msgs::srv::VehicleCommand`](https://github.com/PX4/px4_msgs/blob/main/srv/VehicleCommand.srv).)
This service can be called by ROS 2 applications to send PX4 [VehicleCommand](../msg_docs/VehicleCommand.md) uORB messages and receive PX4 [VehicleCommandAck](../msg_docs/VehicleCommandAck.md) uORB messages in response.
This service can be called by ROS 2 applications to send PX4 [VehicleCommand](../msg_docs/VehicleCommand.md) uORB messages and receive PX4 [VehicleCommandAck](../msg_docs/VehicleCommandAck.md) uORB messages in response.
All PX4 service names follow the convention `{extra_namespace}/fmu/{server_specific_name}` where `{extra_namespace}` is the same [custom namespace](#customizing-the-namespace) that can be given to the PX4 topics.
@@ -973,36 +973,36 @@ The standard installation should include all the tools needed by ROS 2.
If any are missing, they can be added separately:
- **`colcon`** build tools should be in the development tools.
It can be installed using:
It can be installed using:
```sh
sudo apt install python3-colcon-common-extensions
```
```sh
sudo apt install python3-colcon-common-extensions
```
- The Eigen3 library used by the transforms library should be in the both the desktop and base packages.
It should be installed as shown:
It should be installed as shown:
:::: tabs
:::: tabs
::: tab humble
::: tab humble
```sh
sudo apt install ros-humble-eigen3-cmake-module
```
```sh
sudo apt install ros-humble-eigen3-cmake-module
```
:::
::: tab foxy
::: tab foxy
```sh
sudo apt install ros-foxy-eigen3-cmake-module
```
```sh
sudo apt install ros-foxy-eigen3-cmake-module
```
:::
::::
::::
### ros_gz_bridge not publishing on the \clock topic
+3 -3
View File
@@ -89,9 +89,9 @@ uint8 HIL_STATE_ON = 1
# Current vehicle locomotion method. A vehicle can have different methods (e.g. VTOL transitions from RW to FW method)
uint8 vehicle_type
uint8 VEHICLE_TYPE_ROTARY_WING = 0
uint8 VEHICLE_TYPE_FIXED_WING = 1
uint8 VEHICLE_TYPE_ROVER = 2
uint8 VEHICLE_TYPE_ROTARY_WING = 1
uint8 VEHICLE_TYPE_FIXED_WING = 2
uint8 VEHICLE_TYPE_ROVER = 3
uint8 FAILSAFE_DEFER_STATE_DISABLED = 0
uint8 FAILSAFE_DEFER_STATE_ENABLED = 1
+76 -3
View File
@@ -39,6 +39,7 @@
#include <float.h>
#include <string.h>
#include <math.h>
#include <stdio.h>
#include <drivers/drv_pwm_output.h>
#include <drivers/drv_hrt.h>
@@ -62,7 +63,7 @@ struct msp_message_descriptor_t {
uint8_t message_size;
};
#define MSP_DESCRIPTOR_COUNT 11
#define MSP_DESCRIPTOR_COUNT 12
const msp_message_descriptor_t msp_message_descriptors[MSP_DESCRIPTOR_COUNT] = {
{MSP_OSD_CONFIG, true, sizeof(msp_osd_config_t)},
{MSP_NAME, true, sizeof(msp_name_t)},
@@ -75,10 +76,9 @@ const msp_message_descriptor_t msp_message_descriptors[MSP_DESCRIPTOR_COUNT] = {
{MSP_COMP_GPS, true, sizeof(msp_comp_gps_t)},
{MSP_ESC_SENSOR_DATA, true, sizeof(msp_esc_sensor_data_dji_t)},
{MSP_MOTOR_TELEMETRY, true, sizeof(msp_motor_telemetry_t)},
{MSP_RC, true, sizeof(msp_rc_t)},
};
#define MSP_FRAME_START_SIZE 5
#define MSP_CRC_SIZE 1
bool MspV1::Send(const uint8_t message_id, const void *payload)
{
uint32_t payload_size = 0;
@@ -149,3 +149,76 @@ bool MspV1::Send(const uint8_t message_id, const void *payload, uint32_t payload
int packet_size = MSP_FRAME_START_SIZE + payload_size + MSP_CRC_SIZE;
return write(_fd, packet, packet_size) == packet_size;
}
int MspV1::Receive(uint8_t *payload, uint8_t *message_id)
{
uint8_t payload_size;
uint8_t crc;
uint8_t calc_crc;
int ret;
while (!has_header) {
int bytes_available = 0;
if (ioctl(_fd, FIONREAD, &bytes_available) < 0) {
return -EIO;
}
if (bytes_available < 5) {
return -EWOULDBLOCK;
}
while (bytes_available > 4) {
if ((ret = read(_fd, header, 1)) != 1) {
return ret;
}
bytes_available--;
if (header[0] == '$') {
break;
}
}
if (header[0] != '$') {
return -EWOULDBLOCK;
}
if ((ret = read(_fd, &header[1], 4)) != 4) {
return ret;
}
if (header[0] == '$' && header[1] == 'M' && header[2] == '<') {
has_header = true;
}
}
payload_size = header[3];
*message_id = header[4];
if ((ret = read(_fd, payload, payload_size + MSP_CRC_SIZE)) != payload_size + MSP_CRC_SIZE) {
if (ret != -EWOULDBLOCK) {
has_header = false;
}
return ret;
}
has_header = false;
crc = payload[payload_size];
calc_crc = payload_size ^ header[4];
for (int i = 0; i < payload_size; i++) {
calc_crc ^= payload[i];
}
if (calc_crc != crc) {
return -EINVAL;
}
return payload_size;
}
+6
View File
@@ -33,6 +33,9 @@
#pragma once
#define MSP_FRAME_START_SIZE 5
#define MSP_CRC_SIZE 1
class MspV1
{
public:
@@ -40,7 +43,10 @@ public:
int GetMessageSize(int message_type);
bool Send(const uint8_t message_id, const void *payload);
bool Send(const uint8_t message_id, const void *payload, uint32_t payload_size);
int Receive(uint8_t *payload, uint8_t *message_id);
private:
int _fd{-1};
uint8_t header[MSP_FRAME_START_SIZE + MSP_CRC_SIZE];
bool has_header{false};
};
+11
View File
@@ -97,3 +97,14 @@ parameters:
min: 100
max: 10000
default: 500
# RC Stick input
OSD_RC_STICK:
description:
short: OSD RC Stick commands
long: |
Forward RC stick input to VTX when disarmed
type: int32
min: 0
max: 1
default: 1
+60 -4
View File
@@ -48,6 +48,8 @@
#define MSP_ARMING_CONFIG 61
#define MSP_RX_MAP 64 // get channel map (also returns number of channels total)
#define MSP_LOOP_TIME 73 // FC cycle time i.e looptime parameter
#define MSP_GET_VTX_CONFIG 88
#define MSP_SET_VTX_CONFIG 89
#define MSP_STATUS 101
#define MSP_RAW_IMU 102
#define MSP_SERVO 103
@@ -75,10 +77,12 @@
#define MSP_SET_PID 202 // set P I D coeff
// commands
#define MSP_SET_HEAD 211 // define a new heading hold direction
#define MSP_SET_RAW_RC 200 // 8 rc chan
#define MSP_SET_RAW_GPS 201 // fix, numsat, lat, lon, alt, speed
#define MSP_SET_WP 209 // sets a given WP (WP#, lat, lon, alt, flags)
#define MSP_SET_HEAD 211 // define a new heading hold direction
#define MSP_SET_RAW_RC 200 // 8 rc chan
#define MSP_SET_RAW_GPS 201 // fix, numsat, lat, lon, alt, speed
#define MSP_SET_WP 209 // sets a given WP (WP#, lat, lon, alt, flags)
#define MSP_SET_VTXTABLE_BAND 227
#define MSP_SET_VTXTABLE_POWERLEVEL 228
// bits of getActiveModes() return value
#define MSP_MODE_ARM 0
@@ -895,6 +899,58 @@ struct msp_status_BF_t {
uint8_t extra_flags;
} __attribute__((packed));
struct msp_set_vtx_config_t {
uint16_t new_freq; // if setting frequency then full uint16 is the frequency in MHz (ie. 5800)
//if setting band channel than band is high 8 bits and channel is low 8 bits
uint8_t power_level;
uint8_t pit_mode; // 0 = off, 1 = on
uint8_t low_power_disarm;
uint16_t pit_freq;
uint8_t user_band;
uint8_t user_channel;
uint16_t user_freq; // in MHz, 0 if using band & channel
uint8_t band_count;
uint8_t channel_count;
uint8_t power_count;
uint8_t clear_vtxtable; // Bool
} __attribute__((packed));
struct msp_get_vtx_config_t {
uint8_t vtx_type;
uint8_t band;
uint8_t channel;
uint8_t power_index;
uint8_t pit_mode; // 0 = off, 1 = on
uint16_t freq; // in MHz, 0 if using band & channel
uint8_t device_ready;
uint8_t low_power_disarm;
} __attribute__((packed));
struct msp_set_vtxtable_powerlevel_t {
uint8_t index;
uint16_t power_value;
uint8_t power_label_length;
uint8_t power_label_name[3];
} __attribute__((packed));
#define VTX_TABLE_BAND_NAME_LENGTH 8
#define VTXDEV_MSP 5
//29 bytes
struct msp_set_vtxtable_band_t {
uint8_t band;
uint8_t band_name_length;
uint8_t band_label_name[VTX_TABLE_BAND_NAME_LENGTH];
uint8_t band_letter;
uint8_t is_factory_band;
uint8_t channel_count;
uint16_t frequency[8];
} __attribute__((packed));
////ArduPlane
enum arduPlaneModes_e {
MANUAL = 0,
+189
View File
@@ -47,6 +47,7 @@
#include <unistd.h>
#include <termios.h>
#include <string.h>
#include <ctype.h>
#include <px4_platform_common/getopt.h>
#include <px4_platform_common/log.h>
@@ -239,6 +240,7 @@ void MspOsd::SendConfig()
_msp.Send(MSP_OSD_CONFIG, &msp_osd_config);
}
// extract it to MSPOSD_BF_Run() and MSPOSD_DJIFPV_Run() for compatibility?
void MspOsd::Run()
{
@@ -280,6 +282,23 @@ void MspOsd::Run()
_is_initialized = true;
}
if (change_channel) {
msp_get_vtx_config_t vtx_set_config{0};
vtx_set_config.low_power_disarm = vtx_config.low_power_disarm;
vtx_set_config.pit_mode = vtx_config.pit_mode;
vtx_set_config.vtx_type = VTXDEV_MSP;
vtx_set_config.band = vtx_config.user_band;
vtx_set_config.channel = vtx_config.user_channel;
this->Send(MSP_GET_VTX_CONFIG, &vtx_set_config, sizeof(msp_get_vtx_config_t));
change_channel = false;
}
this->Receive();
if (!has_vtx_config) {
this->Send(MSP_GET_VTX_CONFIG, nullptr, 0);
}
// avoid premature pessimization; if skip processing if we're effectively disabled
if (_param_osd_symbols.get() == 0) {
return;
@@ -420,6 +439,32 @@ void MspOsd::Run()
{
}
// MSP_RC
{
if (_param_osd_rc_stick.get() == 1) {
vehicle_status_s vehicle_status{};
_vehicle_status_sub.copy(&vehicle_status);
if (vehicle_status.arming_state != vehicle_status_s::ARMING_STATE_ARMED) {
input_rc_s input_rc{};
_input_rc_sub.copy(&input_rc);
const auto msg = msp_osd::construct_MSP_RC(input_rc);
this->Send(MSP_RC, &msg, sizeof(msp_rc_t));
}
}
}
// MSP_STATUS
{
vehicle_status_s vehicle_status{};
_vehicle_status_sub.copy(&vehicle_status);
const auto msg = msp_osd::construct_MSP_STATUS(vehicle_status);
this->Send(MSP_STATUS, &msg, sizeof(msp_status_t));
}
subcmd = MSP_DP_DRAW_SCREEN;
this->Send(MSP_CMD_DISPLAYPORT, &subcmd, 1);
}
@@ -443,6 +488,58 @@ void MspOsd::Send(const unsigned int message_type, const void *payload, int32_t
}
}
void MspOsd::Receive()
{
uint8_t packet[255];
uint8_t message_id;
int ret;
while ((ret = _msp.Receive(packet, &message_id)) != -EWOULDBLOCK) {
if (ret >= 0) {
switch (message_id) {
case MSP_SET_VTX_CONFIG: {
if (ret == 0xF) {
memcpy((void *)&vtx_config, packet, sizeof(vtx_config));
has_vtx_config = true;
}
break;
}
case MSP_SET_VTXTABLE_BAND: {
msp_set_vtxtable_band_t *band_info = (msp_set_vtxtable_band_t *)&packet[0];
// Only supported fixed name lenght and < 8 channels for now
if (band_info->band <= BAND_COUNT && band_info->band_name_length == 8 && band_info->channel_count <= 8) {
memcpy((void *)&vtx_bands[band_info->band - 1], packet, sizeof(msp_set_vtxtable_band_t));
if (has_vtx_config && band_info->band == vtx_config.band_count) {
has_vtx_bands = true;
}
}
break;
}
case MSP_SET_VTXTABLE_POWERLEVEL: {
if ((packet[0] - 1) < POWER_LEVEL_COUNT) {
memcpy((void *)&power_levels[packet[0] - 1], packet, sizeof(msp_set_vtxtable_powerlevel_t));
has_power_config = true;
}
break;
}
default:
break;
}
}
}
}
void MspOsd::parameters_update()
{
// update our display rate and dwell time
@@ -523,11 +620,102 @@ int MspOsd::print_status()
_display.get(msg, hrt_absolute_time());
PX4_INFO("Current message: \n\t%s", msg);
if (has_vtx_config) {
PX4_INFO("=== VTX Configuration ===");
if (has_vtx_bands) {
PX4_INFO("Channel: %c%u", vtx_bands[vtx_config.user_band - 1].band_letter, vtx_config.user_channel);
} else {
PX4_INFO("Band: %u", vtx_config.user_band);
PX4_INFO("Channel: %u", vtx_config.user_channel);
}
PX4_INFO("Frequency: %u MHz", vtx_config.user_freq);
if (has_power_config && (vtx_config.power_level - 1) < POWER_LEVEL_COUNT) {
PX4_INFO("Transmit power: %.*s mW", power_levels[vtx_config.power_level - 1].power_label_length,
power_levels[vtx_config.power_level - 1].power_label_name);
} else {
PX4_INFO("Power Level: %u/%u", vtx_config.power_level, vtx_config.power_count);
}
PX4_INFO("PIT Mode: %s", vtx_config.pit_mode ? "On" : "Off");
const char *disarm_modes[] = {
"Off",
"Always",
"Until First Arm"
};
if (vtx_config.low_power_disarm < 3) {
PX4_INFO("Low Power Disarm: %s", disarm_modes[vtx_config.low_power_disarm]);
} else {
PX4_INFO("Low Power Disarm: Unknown (%u)", vtx_config.low_power_disarm);
}
PX4_INFO("PIT Frequency: %u MHz", vtx_config.pit_freq);
} else {
PX4_INFO("No VTX Configuration available, can't do channel switching");
}
return 0;
}
int MspOsd::set_channel(char *new_channel)
{
char band_letter = toupper(new_channel[0]);
if (!has_vtx_bands) {
return -2;
}
for (int i = 0; i < BAND_COUNT; i++) {
if (vtx_bands[i].band != 0) {
if (band_letter == toupper(vtx_bands[i].band_letter)) {
int channel = atoi(&new_channel[1]);
if (channel > 0 && channel <= vtx_config.channel_count && vtx_bands[i].frequency[channel - 1] != 0) {
vtx_config.user_band = vtx_bands[i].band;
vtx_config.user_channel = channel;
vtx_config.user_freq = vtx_bands[i].frequency[channel - 1];
change_channel = true;
return 0;
}
}
}
}
return -1;
}
int MspOsd::custom_command(int argc, char *argv[])
{
if (argc > 0 && strcmp("channel", argv[0]) == 0) {
if (argc == 1) {
PX4_INFO("Please provide a channel");
} else if (is_running() && _object.load()) {
MspOsd *object = _object.load();
int ret = object->set_channel(argv[1]);
if (ret == -1) {
PX4_INFO("Channel not found");
} else if (ret == -2) {
PX4_INFO("No VTX Channel table available");
}
} else {
PX4_INFO("not running");
}
}
return 0;
}
@@ -553,6 +741,7 @@ $ msp_osd
PRINT_MODULE_USAGE_NAME("msp_osd", "driver");
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
PRINT_MODULE_USAGE_COMMAND_DESCR("channel", "Change VTX channel");
return 0;
}
+18 -1
View File
@@ -64,6 +64,9 @@ using namespace time_literals;
// location to "hide" unused display elements
#define LOCATION_HIDDEN 234;
#define POWER_LEVEL_COUNT 5
#define BAND_COUNT 7
struct PerformanceData {
bool initialization_problems{false};
long unsigned int successful_sends{0};
@@ -118,6 +121,8 @@ public:
/** @see ModuleBase::print_status() */
int print_status() override;
int set_channel(char *new_channel);
private:
void Run() override;
@@ -125,6 +130,9 @@ private:
void Send(const unsigned int message_type, const void *payload);
void Send(const unsigned int message_type, const void *payload, int32_t payload_size);
// receive vtx data
void Receive();
// send full configuration to MSP (triggers the actual update)
void SendConfig();
void SendTelemetry();
@@ -166,10 +174,19 @@ private:
(ParamInt<px4::params::OSD_CH_HEIGHT>) _param_osd_ch_height,
(ParamInt<px4::params::OSD_SCROLL_RATE>) _param_osd_scroll_rate,
(ParamInt<px4::params::OSD_DWELL_TIME>) _param_osd_dwell_time,
(ParamInt<px4::params::OSD_LOG_LEVEL>) _param_osd_log_level
(ParamInt<px4::params::OSD_LOG_LEVEL>) _param_osd_log_level,
(ParamInt<px4::params::OSD_RC_STICK>) _param_osd_rc_stick
)
// metadata
char _device[64] {};
PerformanceData _performance_data{};
msp_set_vtx_config_t vtx_config;
msp_set_vtxtable_powerlevel_t power_levels[POWER_LEVEL_COUNT];
msp_set_vtxtable_band_t vtx_bands[BAND_COUNT] {};
bool has_vtx_config {false};
bool has_power_config {false};
bool has_vtx_bands {false};
bool change_channel {false};
};
+28 -8
View File
@@ -214,14 +214,8 @@ msp_rendor_rssi_t construct_rendor_RSSI(const input_rc_s &input_rc)
rssi.screenYPosition = 0x02;
rssi.screenXPosition = 0x02;
int len = snprintf(&rssi.str[0], sizeof(rssi.str) - 1, "%d", input_rc.link_quality);
if (len >= 3) {
rssi.str[3] = '%';
} else {
rssi.str[len] = '%';
}
snprintf(&rssi.str[0], sizeof(rssi.str), "%3d", input_rc.link_quality);
rssi.str[3] = '%';
return rssi;
}
@@ -569,4 +563,30 @@ msp_esc_sensor_data_dji_t construct_ESC_SENSOR_DATA()
return esc_sensor_data;
}
msp_rc_t construct_MSP_RC(const input_rc_s &input_rc)
{
// initialize result
msp_rc_t rc;
rc.channelValue[0] = input_rc.values[0]; // roll
rc.channelValue[1] = input_rc.values[1]; // pitch
rc.channelValue[2] = input_rc.values[3]; // yaw
rc.channelValue[3] = input_rc.values[2]; // Throttle
return rc;
}
msp_status_t construct_MSP_STATUS(const vehicle_status_s &vehicle_status)
{
// initialize result
msp_status_t status{0};
if (vehicle_status.arming_state == vehicle_status_s::ARMING_STATE_ARMED) {
status.flightModeFlags |= (1 << MSP_MODE_ARM);
}
return status;
}
} // namespace msp_osd
+6
View File
@@ -126,4 +126,10 @@ msp_rendor_distanceToHome_t construct_rendor_distanceToHome(const home_position_
// construct an MSP_ESC_SENSOR_DATA struct
msp_esc_sensor_data_dji_t construct_ESC_SENSOR_DATA();
// construct an MSP_RC struct
msp_rc_t construct_MSP_RC(const input_rc_s &input_rc);
// construct an MSP_STATUS struct
msp_status_t construct_MSP_STATUS(const vehicle_status_s &vehicle_status);
} // namespace msp_osd
+6
View File
@@ -31,10 +31,12 @@
#
############################################################################
add_subdirectory(MecanumActControl)
add_subdirectory(MecanumRateControl)
add_subdirectory(MecanumAttControl)
add_subdirectory(MecanumVelControl)
add_subdirectory(MecanumPosControl)
add_subdirectory(MecanumDriveModes)
px4_add_module(
MODULE modules__rover_mecanum
@@ -43,10 +45,14 @@ px4_add_module(
RoverMecanum.cpp
RoverMecanum.hpp
DEPENDS
MecanumActControl
MecanumRateControl
MecanumAttControl
MecanumVelControl
MecanumPosControl
MecanumAutoMode
MecanumManualMode
MecanumOffboardMode
px4_work_queue
rover_control
pure_pursuit
@@ -0,0 +1,38 @@
############################################################################
#
# Copyright (c) 2025 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_library(MecanumActControl
MecanumActControl.cpp
)
target_include_directories(MecanumActControl PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})
@@ -0,0 +1,129 @@
/****************************************************************************
*
* Copyright (c) 2025 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include "MecanumActControl.hpp"
using namespace time_literals;
MecanumActControl::MecanumActControl(ModuleParams *parent) : ModuleParams(parent)
{
updateParams();
}
void MecanumActControl::updateParams()
{
ModuleParams::updateParams();
if (_param_ro_accel_limit.get() > FLT_EPSILON && _param_ro_max_thr_speed.get() > FLT_EPSILON) {
_adjusted_throttle_x_setpoint.setSlewRate(_param_ro_accel_limit.get() / _param_ro_max_thr_speed.get());
_adjusted_throttle_y_setpoint.setSlewRate(_param_ro_accel_limit.get() / _param_ro_max_thr_speed.get());
}
}
void MecanumActControl::updateActControl()
{
const hrt_abstime timestamp_prev = _timestamp;
_timestamp = hrt_absolute_time();
const float dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 5000_ms) * 1e-6f;
// Motor control
if (_rover_throttle_setpoint_sub.updated()) {
rover_throttle_setpoint_s rover_throttle_setpoint{};
_rover_throttle_setpoint_sub.copy(&rover_throttle_setpoint);
_throttle_x_setpoint = rover_throttle_setpoint.throttle_body_x;
_throttle_y_setpoint = rover_throttle_setpoint.throttle_body_y;
}
if (_rover_steering_setpoint_sub.updated()) {
rover_steering_setpoint_s rover_steering_setpoint{};
_rover_steering_setpoint_sub.copy(&rover_steering_setpoint);
_speed_diff_setpoint = rover_steering_setpoint.normalized_speed_diff;
}
if (PX4_ISFINITE(_throttle_x_setpoint) && PX4_ISFINITE(_throttle_y_setpoint) && PX4_ISFINITE(_speed_diff_setpoint)) {
actuator_motors_s actuator_motors_sub{};
_actuator_motors_sub.copy(&actuator_motors_sub);
const float current_throttle_x = (actuator_motors_sub.control[0] + actuator_motors_sub.control[1]) / 2.f;
const float current_throttle_y = (actuator_motors_sub.control[2] - actuator_motors_sub.control[0]) / 2.f;
const float adjusted_throttle_x_setpoint = RoverControl::throttleControl(_adjusted_throttle_x_setpoint,
_throttle_x_setpoint, current_throttle_x, _param_ro_accel_limit.get(),
_param_ro_decel_limit.get(), _param_ro_max_thr_speed.get(), dt);
const float adjusted_throttle_y_setpoint = RoverControl::throttleControl(_adjusted_throttle_y_setpoint,
_throttle_y_setpoint, current_throttle_y, _param_ro_accel_limit.get(),
_param_ro_decel_limit.get(), _param_ro_max_thr_speed.get(), dt);
actuator_motors_s actuator_motors{};
actuator_motors.reversible_flags = _param_r_rev.get();
computeInverseKinematics(adjusted_throttle_x_setpoint, adjusted_throttle_y_setpoint,
_speed_diff_setpoint).copyTo(actuator_motors.control);
actuator_motors.timestamp = _timestamp;
_actuator_motors_pub.publish(actuator_motors);
}
}
Vector4f MecanumActControl::computeInverseKinematics(float throttle_body_x, float throttle_body_y,
const float speed_diff_normalized)
{
const float total_speed = fabsf(throttle_body_x) + fabsf(throttle_body_y) + fabsf(speed_diff_normalized);
if (total_speed > 1.f) { // Adjust speed setpoints if infeasible
const float theta = atan2f(fabsf(throttle_body_y), fabsf(throttle_body_x));
const float magnitude = (1.f - fabsf(speed_diff_normalized)) / (sinf(theta) + cosf(theta));
const float normalization = 1.f / (sqrtf(powf(throttle_body_x, 2.f) + powf(throttle_body_y, 2.f)));
throttle_body_x *= magnitude * normalization;
throttle_body_y *= magnitude * normalization;
}
// Calculate motor commands
const float input_data[3] = {throttle_body_x, throttle_body_y, speed_diff_normalized};
const Matrix<float, 3, 1> input(input_data);
const float m_data[12] = {1.f, -1.f, -1.f, 1.f, 1.f, 1.f, 1.f, 1.f, -1.f, 1.f, -1.f, 1.f};
const Matrix<float, 4, 3> m(m_data);
const Vector4f motor_commands = m * input;
return motor_commands;
}
void MecanumActControl::stopVehicle()
{
actuator_motors_s actuator_motors{};
actuator_motors.reversible_flags = _param_r_rev.get();
actuator_motors.control[0] = 0.f;
actuator_motors.control[1] = 0.f;
actuator_motors.control[2] = 0.f;
actuator_motors.control[3] = 0.f;
actuator_motors.timestamp = _timestamp;
_actuator_motors_pub.publish(actuator_motors);
}
@@ -0,0 +1,115 @@
/****************************************************************************
*
* Copyright (c) 2025 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
// PX4 includes
#include <px4_platform_common/module_params.h>
// Libraries
#include <lib/rover_control/RoverControl.hpp>
#include <lib/slew_rate/SlewRate.hpp>
#include <math.h>
// uORB includes
#include <uORB/Subscription.hpp>
#include <uORB/Publication.hpp>
#include <uORB/topics/actuator_motors.h>
#include <uORB/topics/rover_steering_setpoint.h>
#include <uORB/topics/rover_throttle_setpoint.h>
/**
* @brief Class for mecanum actuator control.
*/
class MecanumActControl : public ModuleParams
{
public:
/**
* @brief Constructor for MecanumActControl.
* @param parent The parent ModuleParams object.
*/
MecanumActControl(ModuleParams *parent);
~MecanumActControl() = default;
/**
* @brief Generate and publish actuatorMotors setpoints from roverThrottleSetpoint/roverSteeringSetpoint.
*/
void updateActControl();
/**
* @brief Stop the vehicle by sending 0 commands to motors and servos.
*/
void stopVehicle();
protected:
/**
* @brief Update the parameters of the module.
*/
void updateParams() override;
private:
/**
* @brief Compute normalized motor commands based on normalized setpoints.
* @param throttle_body_x Normalized speed in body x direction [-1, 1].
* @param throttle_body_y Normalized speed in body y direction [-1, 1].
* @param speed_diff_normalized Speed difference between left and right wheels [-1, 1].
* @return Motor speeds [-1, 1].
*/
Vector4f computeInverseKinematics(float throttle_body_x, float throttle_body_y, const float speed_diff_normalized);
// uORB subscriptions
uORB::Subscription _actuator_motors_sub{ORB_ID(actuator_motors)};
uORB::Subscription _rover_steering_setpoint_sub{ORB_ID(rover_steering_setpoint)};
uORB::Subscription _rover_throttle_setpoint_sub{ORB_ID(rover_throttle_setpoint)};
// uORB publications
uORB::Publication<actuator_motors_s> _actuator_motors_pub{ORB_ID(actuator_motors)};
// Variables
hrt_abstime _timestamp{0};
float _throttle_x_setpoint{NAN};
float _throttle_y_setpoint{NAN};
float _speed_diff_setpoint{NAN};
// Controllers
SlewRate<float> _adjusted_throttle_x_setpoint{0.f};
SlewRate<float> _adjusted_throttle_y_setpoint{0.f};
// Parameters
DEFINE_PARAMETERS(
(ParamInt<px4::params::CA_R_REV>) _param_r_rev,
(ParamFloat<px4::params::RO_ACCEL_LIM>) _param_ro_accel_limit,
(ParamFloat<px4::params::RO_DECEL_LIM>) _param_ro_decel_limit,
(ParamFloat<px4::params::RO_MAX_THR_SPEED>) _param_ro_max_thr_speed
)
};
@@ -38,8 +38,6 @@ using namespace time_literals;
MecanumAttControl::MecanumAttControl(ModuleParams *parent) : ModuleParams(parent)
{
_rover_rate_setpoint_pub.advertise();
_rover_throttle_setpoint_pub.advertise();
_rover_attitude_setpoint_pub.advertise();
_rover_attitude_status_pub.advertise();
updateParams();
}
@@ -52,21 +50,20 @@ void MecanumAttControl::updateParams()
_max_yaw_rate = _param_ro_yaw_rate_limit.get() * M_DEG_TO_RAD_F;
}
// Set up PID controller
_pid_yaw.setGains(_param_ro_yaw_p.get(), 0.f, 0.f);
_pid_yaw.setIntegralLimit(_max_yaw_rate);
_pid_yaw.setOutputLimit(_max_yaw_rate);
// Set up slew rate
_adjusted_yaw_setpoint.setSlewRate(_max_yaw_rate);
}
void MecanumAttControl::updateAttControl()
{
const hrt_abstime timestamp_prev = _timestamp;
hrt_abstime timestamp_prev = _timestamp;
_timestamp = hrt_absolute_time();
_dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 5000_ms) * 1e-6f;
if (_vehicle_control_mode_sub.updated()) {
_vehicle_control_mode_sub.copy(&_vehicle_control_mode);
}
const float dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 5000_ms) * 1e-6f;
if (_vehicle_attitude_sub.updated()) {
vehicle_attitude_s vehicle_attitude{};
@@ -75,17 +72,20 @@ void MecanumAttControl::updateAttControl()
_vehicle_yaw = matrix::Eulerf(vehicle_attitude_quaternion).psi();
}
if (_vehicle_control_mode.flag_control_attitude_enabled && _vehicle_control_mode.flag_armed && runSanityChecks()) {
if (_rover_attitude_setpoint_sub.updated()) {
rover_attitude_setpoint_s rover_attitude_setpoint{};
_rover_attitude_setpoint_sub.copy(&rover_attitude_setpoint);
_yaw_setpoint = rover_attitude_setpoint.yaw_setpoint;
}
if (_vehicle_control_mode.flag_control_manual_enabled || _vehicle_control_mode.flag_control_offboard_enabled) {
generateAttitudeAndThrottleSetpoint();
}
if (PX4_ISFINITE(_yaw_setpoint)) {
const float yaw_rate_setpoint = RoverControl::attitudeControl(_adjusted_yaw_setpoint, _pid_yaw, _max_yaw_rate,
_vehicle_yaw, _yaw_setpoint, dt);
rover_rate_setpoint_s rover_rate_setpoint{};
rover_rate_setpoint.timestamp = _timestamp;
rover_rate_setpoint.yaw_rate_setpoint = math::constrain(yaw_rate_setpoint, -_max_yaw_rate, _max_yaw_rate);
_rover_rate_setpoint_pub.publish(rover_rate_setpoint);
generateRateSetpoint();
} else { // Reset pid and slew rate when attitude control is not active
_pid_yaw.resetIntegral();
_adjusted_yaw_setpoint.setForcedValue(0.f);
}
// Publish attitude controller status (logging only)
@@ -97,93 +97,6 @@ void MecanumAttControl::updateAttControl()
}
void MecanumAttControl::generateAttitudeAndThrottleSetpoint()
{
const bool stab_mode_enabled = _vehicle_control_mode.flag_control_manual_enabled
&& !_vehicle_control_mode.flag_control_position_enabled && _vehicle_control_mode.flag_control_attitude_enabled;
if (stab_mode_enabled && _manual_control_setpoint_sub.updated()) { // Stab Mode
manual_control_setpoint_s manual_control_setpoint{};
if (_manual_control_setpoint_sub.update(&manual_control_setpoint)) {
rover_throttle_setpoint_s rover_throttle_setpoint{};
rover_throttle_setpoint.timestamp = _timestamp;
rover_throttle_setpoint.throttle_body_x = manual_control_setpoint.throttle;
rover_throttle_setpoint.throttle_body_y = manual_control_setpoint.roll;
_rover_throttle_setpoint_pub.publish(rover_throttle_setpoint);
const float yaw_delta = math::interpolate<float>(math::deadzone(manual_control_setpoint.yaw,
_param_ro_yaw_stick_dz.get()), -1.f, 1.f, -_max_yaw_rate / _param_ro_yaw_p.get(),
_max_yaw_rate / _param_ro_yaw_p.get());
if (fabsf(yaw_delta) > FLT_EPSILON) { // Closed loop yaw rate control
_stab_yaw_setpoint = NAN;
const float yaw_setpoint = matrix::wrap_pi(_vehicle_yaw + yaw_delta);
rover_attitude_setpoint_s rover_attitude_setpoint{};
rover_attitude_setpoint.timestamp = _timestamp;
rover_attitude_setpoint.yaw_setpoint = yaw_setpoint;
_rover_attitude_setpoint_pub.publish(rover_attitude_setpoint);
} else { // Closed loop yaw control if the yaw rate input is zero (keep current yaw)
if (!PX4_ISFINITE(_stab_yaw_setpoint)) {
_stab_yaw_setpoint = _vehicle_yaw;
}
rover_attitude_setpoint_s rover_attitude_setpoint{};
rover_attitude_setpoint.timestamp = _timestamp;
rover_attitude_setpoint.yaw_setpoint = _stab_yaw_setpoint;
_rover_attitude_setpoint_pub.publish(rover_attitude_setpoint);
}
}
} else if (_vehicle_control_mode.flag_control_offboard_enabled) { // Offboard attitude control
trajectory_setpoint_s trajectory_setpoint{};
_trajectory_setpoint_sub.copy(&trajectory_setpoint);
if (_offboard_control_mode_sub.updated()) {
_offboard_control_mode_sub.copy(&_offboard_control_mode);
}
const bool offboard_att_control = _offboard_control_mode.attitude;
if (offboard_att_control && PX4_ISFINITE(trajectory_setpoint.yaw)) {
rover_attitude_setpoint_s rover_attitude_setpoint{};
rover_attitude_setpoint.timestamp = _timestamp;
rover_attitude_setpoint.yaw_setpoint = trajectory_setpoint.yaw;
_rover_attitude_setpoint_pub.publish(rover_attitude_setpoint);
}
}
}
void MecanumAttControl::generateRateSetpoint()
{
if (_rover_attitude_setpoint_sub.updated()) {
_rover_attitude_setpoint_sub.copy(&_rover_attitude_setpoint);
}
if (_rover_rate_setpoint_sub.updated()) {
_rover_rate_setpoint_sub.copy(&_rover_rate_setpoint);
}
// Check if a new rate setpoint was already published from somewhere else
if (_rover_rate_setpoint.timestamp > _last_rate_setpoint_update
&& _rover_rate_setpoint.timestamp > _rover_attitude_setpoint.timestamp) {
return;
}
const float yaw_rate_setpoint = RoverControl::attitudeControl(_adjusted_yaw_setpoint, _pid_yaw, _max_yaw_rate,
_vehicle_yaw, _rover_attitude_setpoint.yaw_setpoint, _dt);
_last_rate_setpoint_update = _timestamp;
rover_rate_setpoint_s rover_rate_setpoint{};
rover_rate_setpoint.timestamp = _timestamp;
rover_rate_setpoint.yaw_rate_setpoint = math::constrain(yaw_rate_setpoint, -_max_yaw_rate, _max_yaw_rate);
_rover_rate_setpoint_pub.publish(rover_rate_setpoint);
}
bool MecanumAttControl::runSanityChecks()
{
bool ret = true;
@@ -194,13 +107,9 @@ bool MecanumAttControl::runSanityChecks()
if (_param_ro_yaw_p.get() < FLT_EPSILON) {
ret = false;
if (_prev_param_check_passed) {
events::send<float>(events::ID("mecanum_att_control_conf_invalid_yaw_p"), events::Log::Error,
"Invalid configuration of necessary parameter RO_YAW_P", _param_ro_yaw_p.get());
}
events::send<float>(events::ID("mecanum_att_control_conf_invalid_yaw_p"), events::Log::Error,
"Invalid configuration of necessary parameter RO_YAW_P", _param_ro_yaw_p.get());
}
_prev_param_check_passed = ret;
return ret;
}
@@ -48,15 +48,9 @@
#include <uORB/Publication.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/topics/rover_rate_setpoint.h>
#include <uORB/topics/rover_throttle_setpoint.h>
#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/manual_control_setpoint.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/rover_attitude_status.h>
#include <uORB/topics/rover_attitude_setpoint.h>
#include <uORB/topics/actuator_motors.h>
#include <uORB/topics/offboard_control_mode.h>
#include <uORB/topics/trajectory_setpoint.h>
/**
* @brief Class for mecanum attitude control.
@@ -72,10 +66,21 @@ public:
~MecanumAttControl() = default;
/**
* @brief Update attitude controller.
* @brief Generate and publish roverRateSetpoint from roverAttitudeSetpoint.
*/
void updateAttControl();
/**
* @brief Reset attitude controller.
*/
void reset() {_pid_yaw.resetIntegral(); _yaw_setpoint = NAN;};
/**
* @brief Check if the necessary parameters are set.
* @return True if all checks pass.
*/
bool runSanityChecks();
protected:
/**
* @brief Update the parameters of the module.
@@ -83,51 +88,20 @@ protected:
void updateParams() override;
private:
/**
* @brief Generate and publish roverAttitudeSetpoint and roverThrottleSetpoint from manualControlSetpoint (Stab Mode)
* or trajectorySetpoint (Offboard attitude control).
*/
void generateAttitudeAndThrottleSetpoint();
/**
* @brief Generate and publish roverRateSetpoint from roverAttitudeSetpoint.
*/
void generateRateSetpoint();
/**
* @brief Check if the necessary parameters are set.
* @return True if all checks pass.
*/
bool runSanityChecks();
// uORB subscriptions
uORB::Subscription _vehicle_control_mode_sub{ORB_ID(vehicle_control_mode)};
uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)};
uORB::Subscription _trajectory_setpoint_sub{ORB_ID(trajectory_setpoint)};
uORB::Subscription _offboard_control_mode_sub{ORB_ID(offboard_control_mode)};
uORB::Subscription _vehicle_attitude_sub{ORB_ID(vehicle_attitude)};
uORB::Subscription _actuator_motors_sub{ORB_ID(actuator_motors)};
uORB::Subscription _rover_attitude_setpoint_sub{ORB_ID(rover_attitude_setpoint)};
uORB::Subscription _rover_rate_setpoint_sub{ORB_ID(rover_rate_setpoint)};
vehicle_control_mode_s _vehicle_control_mode{};
rover_attitude_setpoint_s _rover_attitude_setpoint{};
rover_rate_setpoint_s _rover_rate_setpoint{};
offboard_control_mode_s _offboard_control_mode{};
// uORB publications
uORB::Publication<rover_rate_setpoint_s> _rover_rate_setpoint_pub{ORB_ID(rover_rate_setpoint)};
uORB::Publication<rover_throttle_setpoint_s> _rover_throttle_setpoint_pub{ORB_ID(rover_throttle_setpoint)};
uORB::Publication<rover_attitude_setpoint_s> _rover_attitude_setpoint_pub{ORB_ID(rover_attitude_setpoint)};
uORB::Publication<rover_rate_setpoint_s> _rover_rate_setpoint_pub{ORB_ID(rover_rate_setpoint)};
uORB::Publication<rover_attitude_status_s> _rover_attitude_status_pub{ORB_ID(rover_attitude_status)};
// Variables
hrt_abstime _timestamp{0};
hrt_abstime _last_rate_setpoint_update{0};
float _vehicle_yaw{0.f};
float _dt{0.f};
hrt_abstime _timestamp{0};
float _max_yaw_rate{0.f};
float _stab_yaw_setpoint{NAN}; // Yaw setpoint for stab mode, NAN if yaw rate is manually controlled [rad]
bool _prev_param_check_passed{true};
float _yaw_setpoint{NAN};
// Controllers
PID _pid_yaw;
@@ -135,8 +109,8 @@ private:
// Parameters
DEFINE_PARAMETERS(
(ParamFloat<px4::params::RO_YAW_RATE_LIM>) _param_ro_yaw_rate_limit,
(ParamFloat<px4::params::RO_YAW_P>) _param_ro_yaw_p,
(ParamFloat<px4::params::RO_YAW_STICK_DZ>) _param_ro_yaw_stick_dz
(ParamFloat<px4::params::RO_YAW_RATE_LIM>) _param_ro_yaw_rate_limit,
(ParamFloat<px4::params::RO_YAW_P>) _param_ro_yaw_p,
(ParamFloat<px4::params::RO_YAW_STICK_DZ>) _param_ro_yaw_stick_dz
)
};
@@ -0,0 +1,36 @@
############################################################################
#
# Copyright (c) 2025 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
add_subdirectory(MecanumAutoMode)
add_subdirectory(MecanumManualMode)
add_subdirectory(MecanumOffboardMode)
@@ -0,0 +1,38 @@
############################################################################
#
# Copyright (c) 2025 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_library(MecanumAutoMode
MecanumAutoMode.cpp
)
target_include_directories(MecanumAutoMode PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})
@@ -0,0 +1,114 @@
/****************************************************************************
*
* Copyright (c) 2025 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include "MecanumAutoMode.hpp"
using namespace time_literals;
MecanumAutoMode::MecanumAutoMode(ModuleParams *parent) : ModuleParams(parent)
{
updateParams();
_rover_position_setpoint_pub.advertise();
}
void MecanumAutoMode::updateParams()
{
ModuleParams::updateParams();
}
void MecanumAutoMode::autoControl()
{
if (_position_setpoint_triplet_sub.updated()) {
position_setpoint_triplet_s position_setpoint_triplet{};
_position_setpoint_triplet_sub.copy(&position_setpoint_triplet);
int curr_wp_type = position_setpoint_triplet.current.type;
vehicle_local_position_s vehicle_local_position{};
_vehicle_local_position_sub.copy(&vehicle_local_position);
MapProjection global_ned_proj_ref{};
if (!global_ned_proj_ref.isInitialized()
|| (global_ned_proj_ref.getProjectionReferenceTimestamp() != vehicle_local_position.ref_timestamp)) {
global_ned_proj_ref.initReference(vehicle_local_position.ref_lat, vehicle_local_position.ref_lon,
vehicle_local_position.ref_timestamp);
}
Vector2f curr_pos_ned = Vector2f(vehicle_local_position.x, vehicle_local_position.y);
Vector2f curr_wp_ned{NAN, NAN};
Vector2f prev_wp_ned{NAN, NAN};
Vector2f next_wp_ned{NAN, NAN};
RoverControl::globalToLocalSetpointTriplet(curr_wp_ned, prev_wp_ned, next_wp_ned, position_setpoint_triplet,
curr_pos_ned, global_ned_proj_ref);
float waypoint_transition_angle = RoverControl::calcWaypointTransitionAngle(prev_wp_ned, curr_wp_ned, next_wp_ned);
// Waypoint cruising speed
float cruising_speed = position_setpoint_triplet.current.cruising_speed > 0.f ? math::constrain(
position_setpoint_triplet.current.cruising_speed, 0.f, _param_ro_speed_limit.get()) : _param_ro_speed_limit.get();
rover_position_setpoint_s rover_position_setpoint{};
rover_position_setpoint.timestamp = hrt_absolute_time();
rover_position_setpoint.position_ned[0] = curr_wp_ned(0);
rover_position_setpoint.position_ned[1] = curr_wp_ned(1);
rover_position_setpoint.start_ned[0] = prev_wp_ned(0);
rover_position_setpoint.start_ned[1] = prev_wp_ned(1);
rover_position_setpoint.arrival_speed = arrivalSpeed(cruising_speed, waypoint_transition_angle,
_param_ro_speed_limit.get(), _param_rm_miss_spd_gain.get(), curr_wp_type);
rover_position_setpoint.cruising_speed = cruising_speed;
rover_position_setpoint.yaw = PX4_ISFINITE(position_setpoint_triplet.current.yaw) ?
position_setpoint_triplet.current.yaw : NAN;
_rover_position_setpoint_pub.publish(rover_position_setpoint);
}
}
float MecanumAutoMode::arrivalSpeed(const float cruising_speed, const float waypoint_transition_angle,
const float max_speed, const float miss_spd_gain, int curr_wp_type)
{
// Upcoming stop
if (!PX4_ISFINITE(waypoint_transition_angle) || curr_wp_type == position_setpoint_s::SETPOINT_TYPE_LAND
|| curr_wp_type == position_setpoint_s::SETPOINT_TYPE_IDLE) {
return 0.f;
}
// Straight line speed
if (miss_spd_gain > FLT_EPSILON) {
const float speed_reduction = math::constrain(miss_spd_gain * math::interpolate(M_PI_F - waypoint_transition_angle, 0.f,
M_PI_F, 0.f, 1.f), 0.f, 1.f);
return max_speed * (1.f - speed_reduction);
}
return cruising_speed; // Fallthrough
}
@@ -0,0 +1,99 @@
/****************************************************************************
*
* Copyright (c) 2025 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
// PX4 includes
#include <px4_platform_common/module_params.h>
// Libraries
#include <lib/rover_control/RoverControl.hpp>
#include <math.h>
// uORB includes
#include <uORB/Subscription.hpp>
#include <uORB/Publication.hpp>
#include <uORB/topics/vehicle_local_position.h>
#include <uORB/topics/position_setpoint_triplet.h>
#include <uORB/topics/rover_position_setpoint.h>
/**
* @brief Class for Mecanum auto mode.
*/
class MecanumAutoMode : public ModuleParams
{
public:
/**
* @brief Constructor for auto mode.
* @param parent The parent ModuleParams object.
*/
MecanumAutoMode(ModuleParams *parent);
~MecanumAutoMode() = default;
/**
* @brief Generate and publish roverPositionSetpoint from positionSetpointTriplet.
*/
void autoControl();
protected:
/**
* @brief Update the parameters of the module.
*/
void updateParams() override;
private:
/**
* @brief Calculate the speed at which the rover should arrive at the current waypoint. During waypoint transition the speed is restricted to
* Maximum_speed * (1 - normalized_transition_angle * RM_MISS_VEL_GAIN).
* @param cruising_speed Cruising speed [m/s].
* @param waypoint_transition_angle Angle between the prevWP-currWP and currWP-nextWP line segments [rad]
* @param max_speed Maximum speed setpoint [m/s]
* @param miss_spd_gain Tuning parameter for the speed reduction during waypoint transition.
* @param curr_wp_type Type of the current waypoint.
* @return Speed setpoint [m/s].
*/
float arrivalSpeed(const float cruising_speed, const float waypoint_transition_angle, const float max_speed,
const float miss_spd_gain, int curr_wp_type);
// uORB subscriptions
uORB::Subscription _vehicle_local_position_sub{ORB_ID(vehicle_local_position)};
uORB::Subscription _position_setpoint_triplet_sub{ORB_ID(position_setpoint_triplet)};
// uORB publications
uORB::Publication<rover_position_setpoint_s> _rover_position_setpoint_pub{ORB_ID(rover_position_setpoint)};
DEFINE_PARAMETERS(
(ParamFloat<px4::params::RO_SPEED_LIM>) _param_ro_speed_limit,
(ParamFloat<px4::params::RM_MISS_SPD_GAIN>) _param_rm_miss_spd_gain
)
};
@@ -0,0 +1,38 @@
############################################################################
#
# Copyright (c) 2025 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_library(MecanumManualMode
MecanumManualMode.cpp
)
target_include_directories(MecanumManualMode PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})
@@ -0,0 +1,233 @@
/****************************************************************************
*
* Copyright (c) 2025 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include "MecanumManualMode.hpp"
using namespace time_literals;
MecanumManualMode::MecanumManualMode(ModuleParams *parent) : ModuleParams(parent)
{
updateParams();
_rover_throttle_setpoint_pub.advertise();
_rover_steering_setpoint_pub.advertise();
_rover_rate_setpoint_pub.advertise();
_rover_attitude_setpoint_pub.advertise();
_rover_velocity_setpoint_pub.advertise();
_rover_position_setpoint_pub.advertise();
}
void MecanumManualMode::updateParams()
{
ModuleParams::updateParams();
_max_yaw_rate = _param_ro_yaw_rate_limit.get() * M_DEG_TO_RAD_F;
}
void MecanumManualMode::manual()
{
manual_control_setpoint_s manual_control_setpoint{};
_manual_control_setpoint_sub.copy(&manual_control_setpoint);
rover_steering_setpoint_s rover_steering_setpoint{};
rover_steering_setpoint.timestamp = hrt_absolute_time();
rover_steering_setpoint.normalized_speed_diff = manual_control_setpoint.yaw;
_rover_steering_setpoint_pub.publish(rover_steering_setpoint);
rover_throttle_setpoint_s rover_throttle_setpoint{};
rover_throttle_setpoint.timestamp = hrt_absolute_time();
rover_throttle_setpoint.throttle_body_x = manual_control_setpoint.throttle;
rover_throttle_setpoint.throttle_body_y = manual_control_setpoint.roll;
_rover_throttle_setpoint_pub.publish(rover_throttle_setpoint);
}
void MecanumManualMode::acro()
{
manual_control_setpoint_s manual_control_setpoint{};
_manual_control_setpoint_sub.copy(&manual_control_setpoint);
rover_throttle_setpoint_s rover_throttle_setpoint{};
rover_throttle_setpoint.timestamp = hrt_absolute_time();
rover_throttle_setpoint.throttle_body_x = manual_control_setpoint.throttle;
rover_throttle_setpoint.throttle_body_y = manual_control_setpoint.roll;
_rover_throttle_setpoint_pub.publish(rover_throttle_setpoint);
rover_rate_setpoint_s rover_rate_setpoint{};
rover_rate_setpoint.timestamp = hrt_absolute_time();
rover_rate_setpoint.yaw_rate_setpoint = math::interpolate<float> (manual_control_setpoint.yaw, -1.f, 1.f,
-_max_yaw_rate, _max_yaw_rate);
_rover_rate_setpoint_pub.publish(rover_rate_setpoint);
}
void MecanumManualMode::stab()
{
if (_vehicle_attitude_sub.updated()) {
vehicle_attitude_s vehicle_attitude{};
_vehicle_attitude_sub.copy(&vehicle_attitude);
_vehicle_attitude_quaternion = matrix::Quatf(vehicle_attitude.q);
_vehicle_yaw = matrix::Eulerf(_vehicle_attitude_quaternion).psi();
}
manual_control_setpoint_s manual_control_setpoint{};
_manual_control_setpoint_sub.copy(&manual_control_setpoint);
rover_throttle_setpoint_s rover_throttle_setpoint{};
rover_throttle_setpoint.timestamp = hrt_absolute_time();
rover_throttle_setpoint.throttle_body_x = manual_control_setpoint.throttle;
rover_throttle_setpoint.throttle_body_y = manual_control_setpoint.roll;
_rover_throttle_setpoint_pub.publish(rover_throttle_setpoint);
if (fabsf(manual_control_setpoint.yaw) > FLT_EPSILON) {
_stab_yaw_setpoint = NAN;
// Rate control
rover_rate_setpoint_s rover_rate_setpoint{};
rover_rate_setpoint.timestamp = hrt_absolute_time();
rover_rate_setpoint.yaw_rate_setpoint = math::interpolate<float>(math::deadzone(manual_control_setpoint.yaw,
_param_ro_yaw_stick_dz.get()), -1.f, 1.f, -_max_yaw_rate, _max_yaw_rate);
_rover_rate_setpoint_pub.publish(rover_rate_setpoint);
// Set uncontrolled setpoint invalid
rover_attitude_setpoint_s rover_attitude_setpoint{};
rover_attitude_setpoint.timestamp = hrt_absolute_time();
rover_attitude_setpoint.yaw_setpoint = NAN;
_rover_attitude_setpoint_pub.publish(rover_attitude_setpoint);
} else { // Heading control
if (!PX4_ISFINITE(_stab_yaw_setpoint)) {
_stab_yaw_setpoint = _vehicle_yaw;
}
rover_attitude_setpoint_s rover_attitude_setpoint{};
rover_attitude_setpoint.timestamp = hrt_absolute_time();
rover_attitude_setpoint.yaw_setpoint = _stab_yaw_setpoint;
_rover_attitude_setpoint_pub.publish(rover_attitude_setpoint);
}
}
void MecanumManualMode::position()
{
if (_vehicle_attitude_sub.updated()) {
vehicle_attitude_s vehicle_attitude{};
_vehicle_attitude_sub.copy(&vehicle_attitude);
_vehicle_attitude_quaternion = matrix::Quatf(vehicle_attitude.q);
_vehicle_yaw = matrix::Eulerf(_vehicle_attitude_quaternion).psi();
}
if (_vehicle_local_position_sub.updated()) {
vehicle_local_position_s vehicle_local_position{};
_vehicle_local_position_sub.copy(&vehicle_local_position);
_curr_pos_ned = Vector2f(vehicle_local_position.x, vehicle_local_position.y);
}
manual_control_setpoint_s manual_control_setpoint{};
_manual_control_setpoint_sub.copy(&manual_control_setpoint);
Vector3f velocity_setpoint_body{};
velocity_setpoint_body(0) = math::interpolate<float>(manual_control_setpoint.throttle,
-1.f, 1.f, -_param_ro_speed_limit.get(), _param_ro_speed_limit.get());
velocity_setpoint_body(1) = math::interpolate<float>(manual_control_setpoint.roll,
-1.f, 1.f, -_param_ro_speed_limit.get(), _param_ro_speed_limit.get());
velocity_setpoint_body(2) = 0.f;
const Vector3f velocity_setpoint_ned = _vehicle_attitude_quaternion.rotateVector(velocity_setpoint_body);
if (fabsf(manual_control_setpoint.yaw) > FLT_EPSILON || velocity_setpoint_ned.norm() < FLT_EPSILON) {
_pos_ctl_yaw_setpoint = NAN;
// Speed control
rover_velocity_setpoint_s rover_velocity_setpoint{};
rover_velocity_setpoint.timestamp = hrt_absolute_time();
rover_velocity_setpoint.speed = velocity_setpoint_ned.norm();
rover_velocity_setpoint.bearing = atan2f(velocity_setpoint_ned(1), velocity_setpoint_ned(0));
rover_velocity_setpoint.yaw = NAN;
_rover_velocity_setpoint_pub.publish(rover_velocity_setpoint);
// Rate control
rover_rate_setpoint_s rover_rate_setpoint{};
rover_rate_setpoint.timestamp = hrt_absolute_time();
rover_rate_setpoint.yaw_rate_setpoint = math::interpolate<float>(math::deadzone(manual_control_setpoint.yaw,
_param_ro_yaw_stick_dz.get()), -1.f, 1.f, -_max_yaw_rate, _max_yaw_rate);;
_rover_rate_setpoint_pub.publish(rover_rate_setpoint);
// Set uncontrolled setpoints invalid
rover_attitude_setpoint_s rover_attitude_setpoint{};
rover_attitude_setpoint.timestamp = hrt_absolute_time();
rover_attitude_setpoint.yaw_setpoint = NAN;
_rover_attitude_setpoint_pub.publish(rover_attitude_setpoint);
rover_position_setpoint_s rover_position_setpoint{};
rover_position_setpoint.timestamp = hrt_absolute_time();
rover_position_setpoint.position_ned[0] = NAN;
rover_position_setpoint.position_ned[1] = NAN;
rover_position_setpoint.start_ned[0] = NAN;
rover_position_setpoint.start_ned[1] = NAN;
rover_position_setpoint.arrival_speed = NAN;
rover_position_setpoint.cruising_speed = NAN;
rover_position_setpoint.yaw = NAN;
_rover_position_setpoint_pub.publish(rover_position_setpoint);
} else { // Course control
const Vector3f pos_ctl_course_direction_local = velocity_setpoint_ned.normalized();
const Vector2f pos_ctl_course_direction_temp = Vector2f(pos_ctl_course_direction_local(0),
pos_ctl_course_direction_local(1));
// Reset course control if course direction change is above threshold
if (fabsf(acosf(pos_ctl_course_direction_temp(0) * _pos_ctl_course_direction(0) + pos_ctl_course_direction_temp(
1) * _pos_ctl_course_direction(1))) > _param_rm_course_ctl_th.get()) {
_pos_ctl_yaw_setpoint = NAN;
}
if (!PX4_ISFINITE(_pos_ctl_yaw_setpoint)) {
_pos_ctl_start_position_ned = _curr_pos_ned;
_pos_ctl_yaw_setpoint = _vehicle_yaw;
_pos_ctl_course_direction = pos_ctl_course_direction_temp;
}
// Construct a 'target waypoint' for course control s.t. it is never within the maximum lookahead of the rover
const Vector2f start_to_curr_pos = _curr_pos_ned - _pos_ctl_start_position_ned;
const float vector_scaling = fabsf(start_to_curr_pos * _pos_ctl_course_direction) + _param_pp_lookahd_max.get();
const Vector2f target_waypoint_ned = _pos_ctl_start_position_ned + vector_scaling * _pos_ctl_course_direction;
rover_position_setpoint_s rover_position_setpoint{};
rover_position_setpoint.timestamp = hrt_absolute_time();
rover_position_setpoint.position_ned[0] = target_waypoint_ned(0);
rover_position_setpoint.position_ned[1] = target_waypoint_ned(1);
rover_position_setpoint.start_ned[0] = NAN;
rover_position_setpoint.start_ned[1] = NAN;
rover_position_setpoint.arrival_speed = NAN;
rover_position_setpoint.cruising_speed = velocity_setpoint_ned.norm();
rover_position_setpoint.yaw = _pos_ctl_yaw_setpoint;
_rover_position_setpoint_pub.publish(rover_position_setpoint);
}
}
void MecanumManualMode::reset()
{
_stab_yaw_setpoint = NAN;
_pos_ctl_course_direction = Vector2f(NAN, NAN);
_pos_ctl_start_position_ned = Vector2f(NAN, NAN);
_curr_pos_ned = Vector2f(NAN, NAN);
}
@@ -0,0 +1,133 @@
/****************************************************************************
*
* Copyright (c) 2025 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
// PX4 includes
#include <px4_platform_common/module_params.h>
// Libraries
#include <math.h>
#include <matrix/matrix/math.hpp>
// uORB includes
#include <uORB/Subscription.hpp>
#include <uORB/Publication.hpp>
#include <uORB/topics/manual_control_setpoint.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_local_position.h>
#include <uORB/topics/rover_throttle_setpoint.h>
#include <uORB/topics/rover_steering_setpoint.h>
#include <uORB/topics/rover_rate_setpoint.h>
#include <uORB/topics/rover_attitude_setpoint.h>
#include <uORB/topics/rover_velocity_setpoint.h>
#include <uORB/topics/rover_position_setpoint.h>
using namespace matrix;
/**
* @brief Class for Mecanum manual mode.
*/
class MecanumManualMode : public ModuleParams
{
public:
/**
* @brief Constructor for MecanumManualMode.
* @param parent The parent ModuleParams object.
*/
MecanumManualMode(ModuleParams *parent);
~MecanumManualMode() = default;
/**
* @brief Publish roverThrottleSetpoint and roverSteeringSetpoint from manualControlSetpoint.
*/
void manual();
/**
* @brief Generate and publish roverThrottleSetpoint/RoverRateSetpoint from manualControlSetpoint.
*/
void acro();
/**
* @brief Generate and publish roverSetpoints from manualControlSetpoint.
*/
void stab();
/**
* @brief Generate and publish roverSetpoints from manualControlSetpoint.
*/
void position();
/**
* @brief Reset manual mode variables.
*/
void reset();
protected:
/**
* @brief Update the parameters of the module.
*/
void updateParams() override;
private:
// uORB subscriptions
uORB::Subscription _vehicle_attitude_sub{ORB_ID(vehicle_attitude)};
uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)};
uORB::Subscription _vehicle_local_position_sub{ORB_ID(vehicle_local_position)};
// uORB publications
uORB::Publication<rover_throttle_setpoint_s> _rover_throttle_setpoint_pub{ORB_ID(rover_throttle_setpoint)};
uORB::Publication<rover_steering_setpoint_s> _rover_steering_setpoint_pub{ORB_ID(rover_steering_setpoint)};
uORB::Publication<rover_rate_setpoint_s> _rover_rate_setpoint_pub{ORB_ID(rover_rate_setpoint)};
uORB::Publication<rover_attitude_setpoint_s> _rover_attitude_setpoint_pub{ORB_ID(rover_attitude_setpoint)};
uORB::Publication<rover_velocity_setpoint_s> _rover_velocity_setpoint_pub{ORB_ID(rover_velocity_setpoint)};
uORB::Publication<rover_position_setpoint_s> _rover_position_setpoint_pub{ORB_ID(rover_position_setpoint)};
// Variables
Vector2f _pos_ctl_course_direction{NAN, NAN};
Vector2f _pos_ctl_start_position_ned{NAN, NAN};
Vector2f _curr_pos_ned{NAN, NAN};
Quatf _vehicle_attitude_quaternion;
float _pos_ctl_yaw_setpoint{NAN};
float _stab_yaw_setpoint{NAN};
float _vehicle_yaw{NAN};
float _max_yaw_rate{NAN};
DEFINE_PARAMETERS(
(ParamFloat<px4::params::RO_YAW_RATE_LIM>) _param_ro_yaw_rate_limit,
(ParamFloat<px4::params::RO_YAW_STICK_DZ>) _param_ro_yaw_stick_dz,
(ParamFloat<px4::params::PP_LOOKAHD_MAX>) _param_pp_lookahd_max,
(ParamFloat<px4::params::RO_SPEED_LIM>) _param_ro_speed_limit,
(ParamFloat<px4::params::RM_COURSE_CTL_TH>) _param_rm_course_ctl_th
)
};
@@ -0,0 +1,38 @@
############################################################################
#
# Copyright (c) 2025 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_library(MecanumOffboardMode
MecanumOffboardMode.cpp
)
target_include_directories(MecanumOffboardMode PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})
@@ -0,0 +1,92 @@
/****************************************************************************
*
* Copyright (c) 2025 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include "MecanumOffboardMode.hpp"
using namespace time_literals;
MecanumOffboardMode::MecanumOffboardMode(ModuleParams *parent) : ModuleParams(parent)
{
updateParams();
_rover_rate_setpoint_pub.advertise();
_rover_attitude_setpoint_pub.advertise();
_rover_velocity_setpoint_pub.advertise();
_rover_position_setpoint_pub.advertise();
}
void MecanumOffboardMode::updateParams()
{
ModuleParams::updateParams();
}
void MecanumOffboardMode::offboardControl()
{
offboard_control_mode_s offboard_control_mode{};
_offboard_control_mode_sub.copy(&offboard_control_mode);
trajectory_setpoint_s trajectory_setpoint{};
_trajectory_setpoint_sub.copy(&trajectory_setpoint);
if (offboard_control_mode.position) {
rover_position_setpoint_s rover_position_setpoint{};
rover_position_setpoint.timestamp = hrt_absolute_time();
rover_position_setpoint.position_ned[0] = trajectory_setpoint.position[0];
rover_position_setpoint.position_ned[1] = trajectory_setpoint.position[1];
rover_position_setpoint.start_ned[0] = NAN;
rover_position_setpoint.start_ned[1] = NAN;
rover_position_setpoint.cruising_speed = NAN;
rover_position_setpoint.arrival_speed = NAN;
rover_position_setpoint.yaw = NAN;
_rover_position_setpoint_pub.publish(rover_position_setpoint);
} else if (offboard_control_mode.velocity) {
const Vector2f velocity_ned(trajectory_setpoint.velocity[0], trajectory_setpoint.velocity[1]);
rover_velocity_setpoint_s rover_velocity_setpoint{};
rover_velocity_setpoint.timestamp = hrt_absolute_time();
rover_velocity_setpoint.speed = velocity_ned.norm();
rover_velocity_setpoint.bearing = atan2f(velocity_ned(1), velocity_ned(0));
_rover_velocity_setpoint_pub.publish(rover_velocity_setpoint);
} else if (offboard_control_mode.attitude) {
rover_attitude_setpoint_s rover_attitude_setpoint{};
rover_attitude_setpoint.timestamp = hrt_absolute_time();
rover_attitude_setpoint.yaw_setpoint = trajectory_setpoint.yaw;
_rover_attitude_setpoint_pub.publish(rover_attitude_setpoint);
} else if (offboard_control_mode.body_rate) {
rover_rate_setpoint_s rover_rate_setpoint{};
rover_rate_setpoint.timestamp = hrt_absolute_time();
rover_rate_setpoint.yaw_rate_setpoint = trajectory_setpoint.yawspeed;
_rover_rate_setpoint_pub.publish(rover_rate_setpoint);
}
}
@@ -0,0 +1,89 @@
/****************************************************************************
*
* Copyright (c) 2025 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
// PX4 includes
#include <px4_platform_common/module_params.h>
// Libraries
#include <math.h>
#include <matrix/matrix/math.hpp>
// uORB includes
#include <uORB/Subscription.hpp>
#include <uORB/Publication.hpp>
#include <uORB/topics/rover_rate_setpoint.h>
#include <uORB/topics/rover_attitude_setpoint.h>
#include <uORB/topics/rover_velocity_setpoint.h>
#include <uORB/topics/rover_position_setpoint.h>
#include <uORB/topics/offboard_control_mode.h>
#include <uORB/topics/trajectory_setpoint.h>
using namespace matrix;
/**
* @brief Class for Mecanum manual mode.
*/
class MecanumOffboardMode : public ModuleParams
{
public:
/**
* @brief Constructor for MecanumOffboardMode.
* @param parent The parent ModuleParams object.
*/
MecanumOffboardMode(ModuleParams *parent);
~MecanumOffboardMode() = default;
/**
* @brief Generate and publish roverSetpoints from trajectorySetpoint.
*/
void offboardControl();
protected:
/**
* @brief Update the parameters of the module.
*/
void updateParams() override;
private:
// uORB subscriptions
uORB::Subscription _trajectory_setpoint_sub{ORB_ID(trajectory_setpoint)};
uORB::Subscription _offboard_control_mode_sub{ORB_ID(offboard_control_mode)};
// uORB publications
uORB::Publication<rover_rate_setpoint_s> _rover_rate_setpoint_pub{ORB_ID(rover_rate_setpoint)};
uORB::Publication<rover_attitude_setpoint_s> _rover_attitude_setpoint_pub{ORB_ID(rover_attitude_setpoint)};
uORB::Publication<rover_velocity_setpoint_s> _rover_velocity_setpoint_pub{ORB_ID(rover_velocity_setpoint)};
uORB::Publication<rover_position_setpoint_s> _rover_position_setpoint_pub{ORB_ID(rover_position_setpoint)};
};
@@ -38,13 +38,8 @@ using namespace time_literals;
MecanumPosControl::MecanumPosControl(ModuleParams *parent) : ModuleParams(parent)
{
_rover_velocity_setpoint_pub.advertise();
_rover_position_setpoint_pub.advertise();
_pure_pursuit_status_pub.advertise();
// Initially set to NaN to indicate that the rover has no position setpoint
_rover_position_setpoint.position_ned[0] = NAN;
_rover_position_setpoint.position_ned[1] = NAN;
updateParams();
}
@@ -57,28 +52,64 @@ void MecanumPosControl::updateParams()
void MecanumPosControl::updatePosControl()
{
const hrt_abstime timestamp_prev = _timestamp;
_timestamp = hrt_absolute_time();
_dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 5000_ms) * 1e-6f;
updateSubscriptions();
if (_vehicle_control_mode.flag_control_position_enabled && _vehicle_control_mode.flag_armed && runSanityChecks()) {
if (_vehicle_control_mode.flag_control_offboard_enabled) {
generatePositionSetpoint();
hrt_abstime timestamp = hrt_absolute_time();
if (_rover_position_setpoint_sub.updated()) {
_rover_position_setpoint_sub.copy(&_rover_position_setpoint);
_start_ned = Vector2f(_rover_position_setpoint.start_ned[0], _rover_position_setpoint.start_ned[1]);
_start_ned = _start_ned.isAllFinite() ? _start_ned : _curr_pos_ned;
_yaw_setpoint = PX4_ISFINITE(_rover_position_setpoint.yaw) ? _rover_position_setpoint.yaw : _vehicle_yaw;
}
const Vector2f target_waypoint_ned(_rover_position_setpoint.position_ned[0], _rover_position_setpoint.position_ned[1]);
if (target_waypoint_ned.isAllFinite()) {
float distance_to_target = (target_waypoint_ned - _curr_pos_ned).norm();
if (distance_to_target > _param_nav_acc_rad.get()) {
float arrival_speed = PX4_ISFINITE(_rover_position_setpoint.arrival_speed) ? _rover_position_setpoint.arrival_speed :
0.f;
const float distance = arrival_speed > 0.f + FLT_EPSILON ? distance_to_target - _param_nav_acc_rad.get() :
distance_to_target;
float speed_setpoint = math::trajectory::computeMaxSpeedFromDistance(_param_ro_jerk_limit.get(),
_param_ro_decel_limit.get(), distance, fabsf(arrival_speed));
speed_setpoint = math::min(speed_setpoint, _param_ro_speed_limit.get());
if (PX4_ISFINITE(_rover_position_setpoint.cruising_speed)) {
speed_setpoint = sign(_rover_position_setpoint.cruising_speed) * math::min(speed_setpoint,
fabsf(_rover_position_setpoint.cruising_speed));
}
pure_pursuit_status_s pure_pursuit_status{};
pure_pursuit_status.timestamp = timestamp;
const float bearing_setpoint = PurePursuit::calcTargetBearing(pure_pursuit_status, _param_pp_lookahd_gain.get(),
_param_pp_lookahd_max.get(), _param_pp_lookahd_min.get(), target_waypoint_ned, _start_ned,
_curr_pos_ned, fabsf(speed_setpoint));
_pure_pursuit_status_pub.publish(pure_pursuit_status);
rover_velocity_setpoint_s rover_velocity_setpoint{};
rover_velocity_setpoint.timestamp = timestamp;
rover_velocity_setpoint.speed = speed_setpoint;
rover_velocity_setpoint.bearing = speed_setpoint > -FLT_EPSILON ? bearing_setpoint : matrix::wrap_pi(
bearing_setpoint + M_PI_F);
rover_velocity_setpoint.yaw = _yaw_setpoint;
_rover_velocity_setpoint_pub.publish(rover_velocity_setpoint);
} else {
rover_velocity_setpoint_s rover_velocity_setpoint{};
rover_velocity_setpoint.timestamp = timestamp;
rover_velocity_setpoint.speed = 0.f;
rover_velocity_setpoint.bearing = _vehicle_yaw;
_rover_velocity_setpoint_pub.publish(rover_velocity_setpoint);
}
generateVelocitySetpoint();
}
}
void MecanumPosControl::updateSubscriptions()
{
if (_vehicle_control_mode_sub.updated()) {
_vehicle_control_mode_sub.copy(&_vehicle_control_mode);
}
if (_vehicle_attitude_sub.updated()) {
vehicle_attitude_s vehicle_attitude{};
_vehicle_attitude_sub.copy(&vehicle_attitude);
@@ -101,235 +132,6 @@ void MecanumPosControl::updateSubscriptions()
}
void MecanumPosControl::generatePositionSetpoint()
{
if (_offboard_control_mode_sub.updated()) {
_offboard_control_mode_sub.copy(&_offboard_control_mode);
}
if (!_offboard_control_mode.position) {
return;
}
trajectory_setpoint_s trajectory_setpoint{};
_trajectory_setpoint_sub.copy(&trajectory_setpoint);
// Translate trajectory setpoint to rover position setpoint
rover_position_setpoint_s rover_position_setpoint{};
rover_position_setpoint.timestamp = _timestamp;
rover_position_setpoint.position_ned[0] = trajectory_setpoint.position[0];
rover_position_setpoint.position_ned[1] = trajectory_setpoint.position[1];
rover_position_setpoint.cruising_speed = _param_ro_speed_limit.get();
rover_position_setpoint.yaw = _vehicle_yaw;
_rover_position_setpoint_pub.publish(rover_position_setpoint);
}
void MecanumPosControl::generateVelocitySetpoint()
{
if (_vehicle_control_mode.flag_control_manual_enabled && _vehicle_control_mode.flag_control_position_enabled) {
manualPositionMode();
} else if (_vehicle_control_mode.flag_control_auto_enabled) {
autoPositionMode();
} else if (_rover_position_setpoint_sub.copy(&_rover_position_setpoint)
&& PX4_ISFINITE(_rover_position_setpoint.position_ned[0]) && PX4_ISFINITE(_rover_position_setpoint.position_ned[1])) {
goToPositionMode();
}
}
void MecanumPosControl::manualPositionMode()
{
manual_control_setpoint_s manual_control_setpoint{};
_manual_control_setpoint_sub.copy(&manual_control_setpoint);
Vector3f velocity_setpoint_body{};
velocity_setpoint_body(0) = math::interpolate<float>(manual_control_setpoint.throttle,
-1.f, 1.f, -_param_ro_speed_limit.get(), _param_ro_speed_limit.get());
velocity_setpoint_body(1) = math::interpolate<float>(manual_control_setpoint.roll,
-1.f, 1.f, -_param_ro_speed_limit.get(), _param_ro_speed_limit.get());
const float yaw_delta = math::interpolate<float>(math::deadzone(manual_control_setpoint.yaw,
_param_ro_yaw_stick_dz.get()), -1.f, 1.f, -_max_yaw_rate / _param_ro_yaw_p.get(),
_max_yaw_rate / _param_ro_yaw_p.get());
if (fabsf(yaw_delta) > FLT_EPSILON || velocity_setpoint_body.norm() < FLT_EPSILON) { // Closed loop yaw rate control
_pos_ctl_yaw_setpoint = NAN;
const float yaw_setpoint = matrix::wrap_pi(_vehicle_yaw + yaw_delta);
const Vector3f velocity_setpoint_local = _vehicle_attitude_quaternion.rotateVector(velocity_setpoint_body);
rover_velocity_setpoint_s rover_velocity_setpoint{};
rover_velocity_setpoint.timestamp = _timestamp;
rover_velocity_setpoint.speed = velocity_setpoint_body.norm();
rover_velocity_setpoint.bearing = atan2f(velocity_setpoint_local(1), velocity_setpoint_local(0));
rover_velocity_setpoint.yaw = yaw_setpoint;
_rover_velocity_setpoint_pub.publish(rover_velocity_setpoint);
} else { // Course control if the steering input is zero (keep driving on a straight line)
const Vector3f velocity = Vector3f(velocity_setpoint_body(0), velocity_setpoint_body(1), 0.f);
const float velocity_magnitude_setpoint = velocity.norm();
const Vector3f pos_ctl_course_direction_local = _vehicle_attitude_quaternion.rotateVector(velocity.normalized());
const Vector2f pos_ctl_course_direction_temp = Vector2f(pos_ctl_course_direction_local(0),
pos_ctl_course_direction_local(1));
// Reset course control if course direction change is above threshold
if (fabsf(acosf(pos_ctl_course_direction_temp(0) * _pos_ctl_course_direction(0) + pos_ctl_course_direction_temp(
1) * _pos_ctl_course_direction(1))) > _param_rm_course_ctl_th.get()) {
_pos_ctl_yaw_setpoint = NAN;
}
if (!PX4_ISFINITE(_pos_ctl_yaw_setpoint)) {
_pos_ctl_start_position_ned = _curr_pos_ned;
_pos_ctl_yaw_setpoint = _vehicle_yaw;
_pos_ctl_course_direction = pos_ctl_course_direction_temp;
}
// Construct a 'target waypoint' for course control s.t. it is never within the maximum lookahead of the rover
const Vector2f start_to_curr_pos = _curr_pos_ned - _pos_ctl_start_position_ned;
const float vector_scaling = fabsf(start_to_curr_pos * _pos_ctl_course_direction) + _param_pp_lookahd_max.get();
const Vector2f target_waypoint_ned = _pos_ctl_start_position_ned + vector_scaling * _pos_ctl_course_direction;
pure_pursuit_status_s pure_pursuit_status{};
pure_pursuit_status.timestamp = _timestamp;
const float bearing_setpoint = PurePursuit::calcTargetBearing(pure_pursuit_status, _param_pp_lookahd_gain.get(),
_param_pp_lookahd_max.get(), _param_pp_lookahd_min.get(), target_waypoint_ned, _pos_ctl_start_position_ned,
_curr_pos_ned, velocity_magnitude_setpoint);
_pure_pursuit_status_pub.publish(pure_pursuit_status);
rover_velocity_setpoint_s rover_velocity_setpoint{};
rover_velocity_setpoint.timestamp = _timestamp;
rover_velocity_setpoint.speed = velocity_magnitude_setpoint;
rover_velocity_setpoint.bearing = bearing_setpoint;
rover_velocity_setpoint.yaw = _pos_ctl_yaw_setpoint;
_rover_velocity_setpoint_pub.publish(rover_velocity_setpoint);
}
}
void MecanumPosControl::autoPositionMode()
{
if (_position_setpoint_triplet_sub.updated()) {
position_setpoint_triplet_s position_setpoint_triplet{};
_position_setpoint_triplet_sub.copy(&position_setpoint_triplet);
_curr_wp_type = position_setpoint_triplet.current.type;
RoverControl::globalToLocalSetpointTriplet(_curr_wp_ned, _prev_wp_ned, _next_wp_ned, position_setpoint_triplet,
_curr_pos_ned, _global_ned_proj_ref);
_waypoint_transition_angle = RoverControl::calcWaypointTransitionAngle(_prev_wp_ned, _curr_wp_ned, _next_wp_ned);
// Waypoint cruising speed
_auto_speed = position_setpoint_triplet.current.cruising_speed > 0.f ? math::constrain(
position_setpoint_triplet.current.cruising_speed, 0.f, _param_ro_speed_limit.get()) : _param_ro_speed_limit.get();
// Waypoint yaw setpoint
if (PX4_ISFINITE(position_setpoint_triplet.current.yaw)) {
_auto_yaw = position_setpoint_triplet.current.yaw;
} else {
_auto_yaw = _vehicle_yaw;
}
}
const float distance_to_curr_wp = sqrt(powf(_curr_pos_ned(0) - _curr_wp_ned(0),
2) + powf(_curr_pos_ned(1) - _curr_wp_ned(1), 2));
// Check stopping conditions
bool auto_stop{false};
if (_curr_wp_type == position_setpoint_s::SETPOINT_TYPE_LAND
|| _curr_wp_type == position_setpoint_s::SETPOINT_TYPE_IDLE
|| !_next_wp_ned.isAllFinite()) { // Check stopping conditions
auto_stop = distance_to_curr_wp < _param_nav_acc_rad.get();
}
if (auto_stop) {
rover_velocity_setpoint_s rover_velocity_setpoint{};
rover_velocity_setpoint.timestamp = _timestamp;
rover_velocity_setpoint.speed = 0.f;
rover_velocity_setpoint.bearing = 0.f;
rover_velocity_setpoint.yaw = _vehicle_yaw;
_rover_velocity_setpoint_pub.publish(rover_velocity_setpoint);
} else { // Regular guidance algorithm
const float velocity_magnitude = calcVelocityMagnitude(_auto_speed, distance_to_curr_wp, _param_ro_decel_limit.get(),
_param_ro_jerk_limit.get(), _waypoint_transition_angle, _param_ro_speed_limit.get(), _param_rm_miss_spd_gain.get(),
_curr_wp_type);
pure_pursuit_status_s pure_pursuit_status{};
pure_pursuit_status.timestamp = _timestamp;
const float bearing_setpoint = PurePursuit::calcTargetBearing(pure_pursuit_status, _param_pp_lookahd_gain.get(),
_param_pp_lookahd_max.get(), _param_pp_lookahd_min.get(), _curr_wp_ned, _prev_wp_ned, _curr_pos_ned,
velocity_magnitude);
_pure_pursuit_status_pub.publish(pure_pursuit_status);
rover_velocity_setpoint_s rover_velocity_setpoint{};
rover_velocity_setpoint.timestamp = _timestamp;
rover_velocity_setpoint.speed = velocity_magnitude;
rover_velocity_setpoint.bearing = bearing_setpoint;
rover_velocity_setpoint.yaw = _auto_yaw;
_rover_velocity_setpoint_pub.publish(rover_velocity_setpoint);
}
}
float MecanumPosControl::calcVelocityMagnitude(const float auto_speed, const float distance_to_curr_wp,
const float max_decel, const float max_jerk, const float waypoint_transition_angle, const float max_speed,
const float miss_spd_gain, const int curr_wp_type)
{
// Upcoming stop
if (max_decel > FLT_EPSILON && max_jerk > FLT_EPSILON && (!PX4_ISFINITE(waypoint_transition_angle)
|| curr_wp_type == position_setpoint_s::SETPOINT_TYPE_LAND
|| curr_wp_type == position_setpoint_s::SETPOINT_TYPE_IDLE)) {
const float max_velocity_magnitude = math::trajectory::computeMaxSpeedFromDistance(max_jerk,
max_decel, distance_to_curr_wp, 0.f);
return math::constrain(max_velocity_magnitude, -auto_speed, auto_speed);
}
// Straight line speed
if (max_jerk > FLT_EPSILON && max_decel > FLT_EPSILON && miss_spd_gain > FLT_EPSILON) {
const float speed_reduction = math::constrain(miss_spd_gain * math::interpolate(M_PI_F - waypoint_transition_angle, 0.f,
M_PI_F, 0.f, 1.f), 0.f, 1.f);
const float max_velocity_magnitude = math::trajectory::computeMaxSpeedFromDistance(max_jerk, max_decel,
distance_to_curr_wp,
max_speed * (1.f - speed_reduction));
return math::constrain(max_velocity_magnitude, -auto_speed, auto_speed);
}
return auto_speed; // Fallthrough
}
void MecanumPosControl::goToPositionMode()
{
const Vector2f target_waypoint_ned(_rover_position_setpoint.position_ned[0], _rover_position_setpoint.position_ned[1]);
const float distance_to_target = (target_waypoint_ned - _curr_pos_ned).norm();
if (distance_to_target > _param_nav_acc_rad.get()) {
float speed_setpoint = math::trajectory::computeMaxSpeedFromDistance(_param_ro_jerk_limit.get(),
_param_ro_decel_limit.get(), distance_to_target, 0.f);
const float max_speed = PX4_ISFINITE(_rover_position_setpoint.cruising_speed) ?
_rover_position_setpoint.cruising_speed :
_param_ro_speed_limit.get();
speed_setpoint = math::min(speed_setpoint, max_speed);
pure_pursuit_status_s pure_pursuit_status{};
pure_pursuit_status.timestamp = _timestamp;
const float bearing_setpoint = PurePursuit::calcTargetBearing(pure_pursuit_status, _param_pp_lookahd_gain.get(),
_param_pp_lookahd_max.get(), _param_pp_lookahd_min.get(), target_waypoint_ned, _curr_pos_ned,
_curr_pos_ned, fabsf(speed_setpoint));
_pure_pursuit_status_pub.publish(pure_pursuit_status);
rover_velocity_setpoint_s rover_velocity_setpoint{};
rover_velocity_setpoint.timestamp = _timestamp;
rover_velocity_setpoint.speed = speed_setpoint;
rover_velocity_setpoint.bearing = bearing_setpoint;
rover_velocity_setpoint.yaw = _pos_ctl_yaw_setpoint;
_rover_velocity_setpoint_pub.publish(rover_velocity_setpoint);
} else {
rover_velocity_setpoint_s rover_velocity_setpoint{};
rover_velocity_setpoint.timestamp = _timestamp;
rover_velocity_setpoint.speed = 0.f;
rover_velocity_setpoint.bearing = 0.f;
rover_velocity_setpoint.yaw = _vehicle_yaw;
_rover_velocity_setpoint_pub.publish(rover_velocity_setpoint);
}
}
bool MecanumPosControl::runSanityChecks()
{
bool ret = true;
@@ -346,6 +148,5 @@ bool MecanumPosControl::runSanityChecks()
ret = false;
}
_prev_param_check_passed = ret;
return ret;
}
@@ -39,9 +39,7 @@
// Libraries
#include <lib/rover_control/RoverControl.hpp>
#include <lib/pid/PID.hpp>
#include <matrix/matrix/math.hpp>
#include <lib/slew_rate/SlewRate.hpp>
#include <lib/pure_pursuit/PurePursuit.hpp>
#include <lib/geo/geo.h>
#include <math.h>
@@ -51,13 +49,7 @@
#include <uORB/Subscription.hpp>
#include <uORB/topics/rover_velocity_setpoint.h>
#include <uORB/topics/rover_position_setpoint.h>
#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/manual_control_setpoint.h>
#include <uORB/topics/trajectory_setpoint.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/offboard_control_mode.h>
#include <uORB/topics/position_setpoint.h>
#include <uORB/topics/position_setpoint_triplet.h>
#include <uORB/topics/vehicle_local_position.h>
#include <uORB/topics/pure_pursuit_status.h>
@@ -77,10 +69,16 @@ public:
~MecanumPosControl() = default;
/**
* @brief Update position controller.
* @brief Generate and publish roverVelocitySetpoint from roverPositionSetpoint.
*/
void updatePosControl();
/**
* @brief Check if the necessary parameters are set.
* @return True if all checks pass.
*/
bool runSanityChecks();
protected:
/**
* @brief Update the parameters of the module.
@@ -93,101 +91,23 @@ private:
*/
void updateSubscriptions();
/**
* @brief Generate and publish roverPositionSetpoint from position of trajectorySetpoint.
*/
void generatePositionSetpoint();
/**
* @brief Generate and publish roverVelocitySetpoint from manualControlSetpoint (Position Mode) or
* positionSetpointTriplet (Auto Mode) or roverPositionSetpoint.
*/
void generateVelocitySetpoint();
/**
* @brief Generate and publish roverVelocitySetpoint from manualControlSetpoint.
*/
void manualPositionMode();
/**
* @brief Generate and publish roverAttitudeSetpoint from velocity of trajectorySetpoint.
*/
void offboardVelocityMode();
/**
* @brief Generate and publish roverVelocitySetpoint from positionSetpointTriplet.
*/
void autoPositionMode();
/**
* @brief Generate and publish roverVelocitySetpoint from roverPositionSetpoint.
*/
void goToPositionMode();
/**
* @brief Calculate the velocity magnitude setpoint. During waypoint transition the speed is restricted to
* Maximum_speed * (1 - normalized_transition_angle * RM_MISS_VEL_GAIN).
* On straight lines it is based on a speed trajectory such that the rover will arrive at the next waypoint transition
* with the desired waypoiny transition speed under consideration of the maximum deceleration and jerk.
* @param auto_speed Default auto speed [m/s].
* @param distance_to_curr_wp Distance to the current waypoint [m].
* @param max_decel Maximum allowed deceleration [m/s^2].
* @param max_jerk Maximum allowed jerk [m/s^3].
* @param waypoint_transition_angle Angle between the prevWP-currWP and currWP-nextWP line segments [rad]
* @param max_speed Maximum velocity magnitude setpoint [m/s]
* @param miss_spd_gain Tuning parameter for the speed reduction during waypoint transition.
* @param curr_wp_type Type of the current waypoint.
* @return Velocity magnitude setpoint [m/s].
*/
float calcVelocityMagnitude(float auto_speed, float distance_to_curr_wp, float max_decel, float max_jerk,
float waypoint_transition_angle, float max_speed, float miss_spd_gain, int curr_wp_type);
/**
* @brief Check if the necessary parameters are set.
* @return True if all checks pass.
*/
bool runSanityChecks();
// uORB subscriptions
uORB::Subscription _vehicle_control_mode_sub{ORB_ID(vehicle_control_mode)};
uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)};
uORB::Subscription _trajectory_setpoint_sub{ORB_ID(trajectory_setpoint)};
uORB::Subscription _offboard_control_mode_sub{ORB_ID(offboard_control_mode)};
uORB::Subscription _vehicle_attitude_sub{ORB_ID(vehicle_attitude)};
uORB::Subscription _vehicle_local_position_sub{ORB_ID(vehicle_local_position)};
uORB::Subscription _position_setpoint_triplet_sub{ORB_ID(position_setpoint_triplet)};
uORB::Subscription _rover_position_setpoint_sub{ORB_ID(rover_position_setpoint)};
vehicle_control_mode_s _vehicle_control_mode{};
offboard_control_mode_s _offboard_control_mode{};
rover_position_setpoint_s _rover_position_setpoint{};
// uORB publications
uORB::Publication<rover_velocity_setpoint_s> _rover_velocity_setpoint_pub{ORB_ID(rover_velocity_setpoint)};
uORB::Publication<pure_pursuit_status_s> _pure_pursuit_status_pub{ORB_ID(pure_pursuit_status)};
uORB::Publication<rover_position_setpoint_s> _rover_position_setpoint_pub{ORB_ID(rover_position_setpoint)};
uORB::Publication<pure_pursuit_status_s> _pure_pursuit_status_pub{ORB_ID(pure_pursuit_status)};
// Variables
hrt_abstime _timestamp{0};
Quatf _vehicle_attitude_quaternion{};
Vector2f _curr_pos_ned{};
Vector2f _pos_ctl_course_direction{};
Vector2f _pos_ctl_start_position_ned{};
Vector2f _start_ned{};
float _vehicle_yaw{0.f};
float _max_yaw_rate{0.f};
float _pos_ctl_yaw_setpoint{0.f}; // Yaw setpoint for manual position mode, NAN if yaw rate is manually controlled [rad]
float _dt{0.f};
float _auto_speed{0.f};
float _auto_yaw{0.f};
int _curr_wp_type{position_setpoint_s::SETPOINT_TYPE_IDLE};
bool _prev_param_check_passed{true};
// Waypoint variables
Vector2f _curr_wp_ned{};
Vector2f _prev_wp_ned{};
Vector2f _next_wp_ned{};
float _cruising_speed{0.f};
float _waypoint_transition_angle{0.f}; // Angle between the prevWP-currWP and currWP-nextWP line segments [rad]
float _yaw_setpoint{NAN};
// Class Instances
MapProjection _global_ned_proj_ref{}; // Transform global to NED coordinates
@@ -37,8 +37,6 @@ using namespace time_literals;
MecanumRateControl::MecanumRateControl(ModuleParams *parent) : ModuleParams(parent)
{
_rover_rate_setpoint_pub.advertise();
_rover_throttle_setpoint_pub.advertise();
_rover_steering_setpoint_pub.advertise();
_rover_rate_status_pub.advertise();
updateParams();
@@ -47,24 +45,21 @@ MecanumRateControl::MecanumRateControl(ModuleParams *parent) : ModuleParams(pare
void MecanumRateControl::updateParams()
{
ModuleParams::updateParams();
_max_yaw_rate = _param_ro_yaw_rate_limit.get() * M_DEG_TO_RAD_F;
_max_yaw_accel = _param_ro_yaw_accel_limit.get() * M_DEG_TO_RAD_F;
_max_yaw_decel = _param_ro_yaw_decel_limit.get() * M_DEG_TO_RAD_F;
// Set up PID controller
_pid_yaw_rate.setGains(_param_ro_yaw_rate_p.get(), _param_ro_yaw_rate_i.get(), 0.f);
_pid_yaw_rate.setIntegralLimit(1.f);
_pid_yaw_rate.setOutputLimit(1.f);
_adjusted_yaw_rate_setpoint.setSlewRate(_max_yaw_accel);
// Set up slew rate
_adjusted_yaw_rate_setpoint.setSlewRate(_param_ro_yaw_accel_limit.get() * M_DEG_TO_RAD_F);
}
void MecanumRateControl::updateRateControl()
{
const hrt_abstime timestamp_prev = _timestamp;
hrt_abstime timestamp_prev = _timestamp;
_timestamp = hrt_absolute_time();
_dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 5000_ms) * 1e-6f;
if (_vehicle_control_mode_sub.updated()) {
_vehicle_control_mode_sub.copy(&_vehicle_control_mode);
}
const float dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 5000_ms) * 1e-6f;
if (_vehicle_angular_velocity_sub.updated()) {
vehicle_angular_velocity_s vehicle_angular_velocity{};
@@ -73,16 +68,25 @@ void MecanumRateControl::updateRateControl()
vehicle_angular_velocity.xyz[2] : 0.f;
}
if (_vehicle_control_mode.flag_control_rates_enabled && _vehicle_control_mode.flag_armed && runSanityChecks()) {
if (_vehicle_control_mode.flag_control_manual_enabled || _vehicle_control_mode.flag_control_offboard_enabled) {
generateRateAndThrottleSetpoint();
}
if (_rover_rate_setpoint_sub.updated()) {
rover_rate_setpoint_s rover_rate_setpoint{};
_rover_rate_setpoint_sub.copy(&rover_rate_setpoint);
_yaw_rate_setpoint = rover_rate_setpoint.yaw_rate_setpoint;
}
generateSteeringSetpoint();
if (PX4_ISFINITE(_yaw_rate_setpoint)) {
const float yaw_rate_setpoint = fabsf(_yaw_rate_setpoint) > _param_ro_yaw_rate_th.get() * M_DEG_TO_RAD_F ?
_yaw_rate_setpoint : 0.f;
const float speed_diff_normalized = RoverControl::rateControl(_adjusted_yaw_rate_setpoint, _pid_yaw_rate,
yaw_rate_setpoint, _vehicle_yaw_rate, _param_rm_max_thr_yaw_r.get(), _param_ro_yaw_accel_limit.get() * M_DEG_TO_RAD_F,
_param_ro_yaw_decel_limit.get() * M_DEG_TO_RAD_F, _param_rm_wheel_track.get(), dt);
rover_steering_setpoint_s rover_steering_setpoint{};
rover_steering_setpoint.timestamp = _timestamp;
rover_steering_setpoint.normalized_speed_diff = speed_diff_normalized;
_rover_steering_setpoint_pub.publish(rover_steering_setpoint);
} else { // Reset controller and slew rate when rate control is not active
} else {
_pid_yaw_rate.resetIntegral();
_adjusted_yaw_rate_setpoint.setForcedValue(0.f);
}
// Publish rate controller status (logging only)
@@ -95,96 +99,25 @@ void MecanumRateControl::updateRateControl()
}
void MecanumRateControl::generateRateAndThrottleSetpoint()
{
const bool acro_mode_enabled = _vehicle_control_mode.flag_control_manual_enabled
&& !_vehicle_control_mode.flag_control_position_enabled && !_vehicle_control_mode.flag_control_attitude_enabled;
if (acro_mode_enabled && _manual_control_setpoint_sub.updated()) { // Acro Mode
manual_control_setpoint_s manual_control_setpoint{};
if (_manual_control_setpoint_sub.update(&manual_control_setpoint)) {
rover_throttle_setpoint_s rover_throttle_setpoint{};
rover_throttle_setpoint.timestamp = _timestamp;
rover_throttle_setpoint.throttle_body_x = manual_control_setpoint.throttle;
rover_throttle_setpoint.throttle_body_y = manual_control_setpoint.roll;
_rover_throttle_setpoint_pub.publish(rover_throttle_setpoint);
rover_rate_setpoint_s rover_rate_setpoint{};
rover_rate_setpoint.timestamp = _timestamp;
rover_rate_setpoint.yaw_rate_setpoint = math::interpolate<float> (manual_control_setpoint.yaw, -1.f, 1.f,
-_max_yaw_rate, _max_yaw_rate);
_rover_rate_setpoint_pub.publish(rover_rate_setpoint);
}
} else if (_vehicle_control_mode.flag_control_offboard_enabled) { // Offboard rate control
trajectory_setpoint_s trajectory_setpoint{};
_trajectory_setpoint_sub.copy(&trajectory_setpoint);
if (_offboard_control_mode_sub.updated()) {
_offboard_control_mode_sub.copy(&_offboard_control_mode);
}
const bool offboard_rate_control = _offboard_control_mode.body_rate && !_offboard_control_mode.attitude;
if (offboard_rate_control && PX4_ISFINITE(trajectory_setpoint.yawspeed)) {
rover_rate_setpoint_s rover_rate_setpoint{};
rover_rate_setpoint.timestamp = _timestamp;
rover_rate_setpoint.yaw_rate_setpoint = trajectory_setpoint.yawspeed;
_rover_rate_setpoint_pub.publish(rover_rate_setpoint);
}
}
}
void MecanumRateControl::generateSteeringSetpoint()
{
if (_rover_rate_setpoint_sub.updated()) {
_rover_rate_setpoint_sub.copy(&_rover_rate_setpoint);
}
float speed_diff_normalized{0.f};
if (PX4_ISFINITE(_rover_rate_setpoint.yaw_rate_setpoint) && PX4_ISFINITE(_vehicle_yaw_rate)) {
const float yaw_rate_setpoint = fabsf(_rover_rate_setpoint.yaw_rate_setpoint) > _param_ro_yaw_rate_th.get() *
M_DEG_TO_RAD_F ?
_rover_rate_setpoint.yaw_rate_setpoint : 0.f;
speed_diff_normalized = RoverControl::rateControl(_adjusted_yaw_rate_setpoint, _pid_yaw_rate,
yaw_rate_setpoint, _vehicle_yaw_rate, _param_rm_max_thr_yaw_r.get(), _max_yaw_accel,
_max_yaw_decel, _param_rm_wheel_track.get(), _dt);
}
rover_steering_setpoint_s rover_steering_setpoint{};
rover_steering_setpoint.timestamp = _timestamp;
rover_steering_setpoint.normalized_speed_diff = speed_diff_normalized;
_rover_steering_setpoint_pub.publish(rover_steering_setpoint);
}
bool MecanumRateControl::runSanityChecks()
{
bool ret = true;
if (_param_ro_yaw_rate_limit.get() < FLT_EPSILON) {
ret = false;
if (_prev_param_check_passed) {
events::send<float>(events::ID("mecanum_rate_control_conf_invalid_yaw_rate_lim"), events::Log::Error,
"Invalid configuration of necessary parameter RO_YAW_RATE_LIM", _param_ro_yaw_rate_limit.get());
}
events::send<float>(events::ID("mecanum_rate_control_conf_invalid_yaw_rate_lim"), events::Log::Error,
"Invalid configuration of necessary parameter RO_YAW_RATE_LIM", _param_ro_yaw_rate_limit.get());
}
if ((_param_rm_wheel_track.get() < FLT_EPSILON || _param_rm_max_thr_yaw_r.get() < FLT_EPSILON)
&& _param_ro_yaw_rate_p.get() < FLT_EPSILON) {
ret = false;
if (_prev_param_check_passed) {
events::send<float, float, float>(events::ID("mecanum_rate_control_conf_invalid_rate_control"), events::Log::Error,
"Invalid configuration for rate control: Neither feed forward (RM_MAX_THR_YAW_R) nor feedback (RO_YAW_RATE_P) is setup",
_param_rm_wheel_track.get(),
_param_rm_max_thr_yaw_r.get(), _param_ro_yaw_rate_p.get());
}
events::send<float, float, float>(events::ID("mecanum_rate_control_conf_invalid_rate_control"), events::Log::Error,
"Invalid configuration for rate control: Neither feed forward (RM_MAX_THR_YAW_R) nor feedback (RO_YAW_RATE_P) is setup",
_param_rm_wheel_track.get(),
_param_rm_max_thr_yaw_r.get(), _param_ro_yaw_rate_p.get());
}
_prev_param_check_passed = ret;
return ret;
}
@@ -47,15 +47,9 @@
#include <uORB/Publication.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/topics/rover_rate_setpoint.h>
#include <uORB/topics/rover_throttle_setpoint.h>
#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/manual_control_setpoint.h>
#include <uORB/topics/vehicle_angular_velocity.h>
#include <uORB/topics/rover_steering_setpoint.h>
#include <uORB/topics/rover_rate_status.h>
#include <uORB/topics/actuator_motors.h>
#include <uORB/topics/offboard_control_mode.h>
#include <uORB/topics/trajectory_setpoint.h>
/**
* @brief Class for mecanum rate control.
@@ -71,10 +65,21 @@ public:
~MecanumRateControl() = default;
/**
* @brief Update rate controller.
* @brief Generate and publish roverSteeringSetpoint from roverRateSetpoint.
*/
void updateRateControl();
/**
* @brief Check if the necessary parameters are set.
* @return True if all checks pass.
*/
bool runSanityChecks();
/**
* @brief Reset rate controller.
*/
void reset() {_pid_yaw_rate.resetIntegral(); _yaw_rate_setpoint = NAN;};
protected:
/**
* @brief Update the parameters of the module.
@@ -83,48 +88,18 @@ protected:
private:
/**
* @brief Generate and publish roverRateSetpoint and roverThrottleSetpoint from manualControlSetpoint (Acro Mode).
*/
void generateRateAndThrottleSetpoint();
/**
* @brief Generate and publish roverSteeringSetpoint from RoverRateSetpoint.
*/
void generateSteeringSetpoint();
/**
* @brief Check if the necessary parameters are set.
* @return True if all checks pass.
*/
bool runSanityChecks();
// uORB subscriptions
uORB::Subscription _vehicle_control_mode_sub{ORB_ID(vehicle_control_mode)};
uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)};
uORB::Subscription _trajectory_setpoint_sub{ORB_ID(trajectory_setpoint)};
uORB::Subscription _offboard_control_mode_sub{ORB_ID(offboard_control_mode)};
uORB::Subscription _rover_rate_setpoint_sub{ORB_ID(rover_rate_setpoint)};
uORB::Subscription _vehicle_angular_velocity_sub{ORB_ID(vehicle_angular_velocity)};
uORB::Subscription _actuator_motors_sub{ORB_ID(actuator_motors)};
vehicle_control_mode_s _vehicle_control_mode{};
offboard_control_mode_s _offboard_control_mode{};
rover_rate_setpoint_s _rover_rate_setpoint{};
// uORB publications
uORB::Publication<rover_rate_setpoint_s> _rover_rate_setpoint_pub{ORB_ID(rover_rate_setpoint)};
uORB::Publication<rover_throttle_setpoint_s> _rover_throttle_setpoint_pub{ORB_ID(rover_throttle_setpoint)};
uORB::Publication<rover_steering_setpoint_s> _rover_steering_setpoint_pub{ORB_ID(rover_steering_setpoint)};
uORB::Publication<rover_rate_status_s> _rover_rate_status_pub{ORB_ID(rover_rate_status)};
// Variables
hrt_abstime _timestamp{0};
float _max_yaw_rate{0.f};
float _max_yaw_accel{0.f};
float _max_yaw_decel{0.f};
float _vehicle_yaw_rate{0.f};
float _dt{0.f}; // Time since last update [s].
bool _prev_param_check_passed{true};
float _yaw_rate_setpoint{NAN};
// Controllers
PID _pid_yaw_rate;
@@ -39,7 +39,6 @@ MecanumVelControl::MecanumVelControl(ModuleParams *parent) : ModuleParams(parent
{
_rover_throttle_setpoint_pub.advertise();
_rover_attitude_setpoint_pub.advertise();
_rover_velocity_setpoint_pub.advertise();
_rover_velocity_status_pub.advertise();
updateParams();
}
@@ -47,6 +46,8 @@ MecanumVelControl::MecanumVelControl(ModuleParams *parent) : ModuleParams(parent
void MecanumVelControl::updateParams()
{
ModuleParams::updateParams();
// Set up PID controllers
_pid_speed_x.setGains(_param_ro_speed_p.get(), _param_ro_speed_i.get(), 0.f);
_pid_speed_x.setIntegralLimit(1.f);
_pid_speed_x.setOutputLimit(1.f);
@@ -54,9 +55,10 @@ void MecanumVelControl::updateParams()
_pid_speed_y.setIntegralLimit(1.f);
_pid_speed_y.setOutputLimit(1.f);
// Set up slew rates
if (_param_ro_accel_limit.get() > FLT_EPSILON) {
_speed_x_setpoint.setSlewRate(_param_ro_accel_limit.get());
_speed_y_setpoint.setSlewRate(_param_ro_accel_limit.get());
_adjusted_speed_x_setpoint.setSlewRate(_param_ro_accel_limit.get());
_adjusted_speed_y_setpoint.setSlewRate(_param_ro_accel_limit.get());
}
}
@@ -64,31 +66,42 @@ void MecanumVelControl::updateVelControl()
{
const hrt_abstime timestamp_prev = _timestamp;
_timestamp = hrt_absolute_time();
_dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 5000_ms) * 1e-6f;
const float dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 5000_ms) * 1e-6f;
updateSubscriptions();
if ((_vehicle_control_mode.flag_control_velocity_enabled) && _vehicle_control_mode.flag_armed && runSanityChecks()) {
if (_vehicle_control_mode.flag_control_offboard_enabled) { // Offboard Velocity Control
generateVelocitySetpoint();
}
// Attitude Setpoint
if (PX4_ISFINITE(_yaw_setpoint)) {
rover_attitude_setpoint_s rover_attitude_setpoint{};
rover_attitude_setpoint.timestamp = _timestamp;
rover_attitude_setpoint.yaw_setpoint = _yaw_setpoint;
_rover_attitude_setpoint_pub.publish(rover_attitude_setpoint);
generateAttitudeAndThrottleSetpoint();
}
// Throttle Setpoints
if (PX4_ISFINITE(_speed_x_setpoint) && PX4_ISFINITE(_speed_y_setpoint)) {
Vector2f speed_setpoint = calcSpeedSetpoint();
rover_throttle_setpoint_s rover_throttle_setpoint{};
rover_throttle_setpoint.timestamp = _timestamp;
rover_throttle_setpoint.throttle_body_x = RoverControl::speedControl(_adjusted_speed_x_setpoint, _pid_speed_x,
speed_setpoint(0), _vehicle_speed_body_x, _param_ro_accel_limit.get(), _param_ro_decel_limit.get(),
_param_ro_max_thr_speed.get(), dt);
rover_throttle_setpoint.throttle_body_y = RoverControl::speedControl(_adjusted_speed_y_setpoint, _pid_speed_y,
speed_setpoint(1), _vehicle_speed_body_y, _param_ro_accel_limit.get(), _param_ro_decel_limit.get(),
_param_ro_max_thr_speed.get(), dt);
_rover_throttle_setpoint_pub.publish(rover_throttle_setpoint);
} else { // Reset controller and slew rate when velocity control is not active
_pid_speed_x.resetIntegral();
_speed_x_setpoint.setForcedValue(0.f);
_pid_speed_y.resetIntegral();
_speed_y_setpoint.setForcedValue(0.f);
}
// Publish position controller status (logging only)
rover_velocity_status_s rover_velocity_status;
rover_velocity_status.timestamp = _timestamp;
rover_velocity_status.measured_speed_body_x = _vehicle_speed_body_x;
rover_velocity_status.adjusted_speed_body_x_setpoint = _speed_x_setpoint.getState();
rover_velocity_status.adjusted_speed_body_x_setpoint = _adjusted_speed_x_setpoint.getState();
rover_velocity_status.measured_speed_body_y = _vehicle_speed_body_y;
rover_velocity_status.adjusted_speed_body_y_setpoint = _speed_y_setpoint.getState();
rover_velocity_status.adjusted_speed_body_y_setpoint = _adjusted_speed_y_setpoint.getState();
rover_velocity_status.pid_throttle_body_x_integral = _pid_speed_x.getIntegral();
rover_velocity_status.pid_throttle_body_y_integral = _pid_speed_y.getIntegral();
_rover_velocity_status_pub.publish(rover_velocity_status);
@@ -96,10 +109,6 @@ void MecanumVelControl::updateVelControl()
void MecanumVelControl::updateSubscriptions()
{
if (_vehicle_control_mode_sub.updated()) {
_vehicle_control_mode_sub.copy(&_vehicle_control_mode);
}
if (_vehicle_attitude_sub.updated()) {
vehicle_attitude_s vehicle_attitude{};
_vehicle_attitude_sub.copy(&vehicle_attitude);
@@ -116,110 +125,66 @@ void MecanumVelControl::updateSubscriptions()
_vehicle_speed_body_y = fabsf(velocity_in_body_frame(1)) > _param_ro_speed_th.get() ? velocity_in_body_frame(1) : 0.f;
}
}
void MecanumVelControl::generateVelocitySetpoint()
{
trajectory_setpoint_s trajectory_setpoint{};
_trajectory_setpoint_sub.copy(&trajectory_setpoint);
if (_offboard_control_mode_sub.updated()) {
_offboard_control_mode_sub.copy(&_offboard_control_mode);
}
const bool offboard_vel_control = _offboard_control_mode.velocity && !_offboard_control_mode.position;
const Vector2f velocity_in_local_frame(trajectory_setpoint.velocity[0], trajectory_setpoint.velocity[1]);
if (offboard_vel_control && velocity_in_local_frame.isAllFinite()) {
rover_velocity_setpoint_s rover_velocity_setpoint{};
rover_velocity_setpoint.timestamp = _timestamp;
rover_velocity_setpoint.speed = velocity_in_local_frame.norm();
rover_velocity_setpoint.bearing = atan2f(velocity_in_local_frame(1), velocity_in_local_frame(0));
rover_velocity_setpoint.yaw = _vehicle_yaw;
_rover_velocity_setpoint_pub.publish(rover_velocity_setpoint);
}
}
void MecanumVelControl::generateAttitudeAndThrottleSetpoint()
{
if (_rover_velocity_setpoint_sub.updated()) {
_rover_velocity_setpoint_sub.copy(&_rover_velocity_setpoint);
}
rover_velocity_setpoint_s rover_velocity_setpoint;
_rover_velocity_setpoint_sub.copy(&rover_velocity_setpoint);
// Attitude Setpoint
if (PX4_ISFINITE(_rover_velocity_setpoint.yaw)) {
rover_attitude_setpoint_s rover_attitude_setpoint{};
rover_attitude_setpoint.timestamp = _timestamp;
rover_attitude_setpoint.yaw_setpoint = _rover_velocity_setpoint.yaw;
_rover_attitude_setpoint_pub.publish(rover_attitude_setpoint);
_last_attitude_setpoint_update = _timestamp;
if (PX4_ISFINITE(rover_velocity_setpoint.speed) && PX4_ISFINITE(rover_velocity_setpoint.bearing)) {
const Vector3f velocity_in_local_frame(rover_velocity_setpoint.speed * cosf(rover_velocity_setpoint.bearing),
rover_velocity_setpoint.speed * sinf(rover_velocity_setpoint.bearing), 0.f);
const Vector3f velocity_in_body_frame = _vehicle_attitude_quaternion.rotateVectorInverse(velocity_in_local_frame);
_speed_x_setpoint = velocity_in_body_frame(0);
_speed_y_setpoint = velocity_in_body_frame(1);
} else {
rover_attitude_setpoint_s rover_attitude_setpoint{};
rover_attitude_setpoint.timestamp = _timestamp;
rover_attitude_setpoint.yaw_setpoint = _vehicle_yaw;
_rover_attitude_setpoint_pub.publish(rover_attitude_setpoint);
_last_attitude_setpoint_update = _timestamp;
}
} else if (PX4_ISFINITE(rover_velocity_setpoint.speed)) {
_speed_x_setpoint = rover_velocity_setpoint.speed;
_speed_y_setpoint = 0.f;
// Throttle Setpoint
float speed_body_x_setpoint{0.f};
float speed_body_y_setpoint{0.f};
if (fabsf(_rover_velocity_setpoint.speed) > FLT_EPSILON && PX4_ISFINITE(_rover_velocity_setpoint.bearing)) {
const Vector3f velocity_in_local_frame(_rover_velocity_setpoint.speed * cosf(
_rover_velocity_setpoint.bearing),
_rover_velocity_setpoint.speed * sinf(_rover_velocity_setpoint.bearing), 0.f);
const Vector3f velocity_in_body_frame = _vehicle_attitude_quaternion.rotateVectorInverse(velocity_in_local_frame);
speed_body_x_setpoint = velocity_in_body_frame(0);
speed_body_y_setpoint = velocity_in_body_frame(1);
} else {
speed_body_x_setpoint = _rover_velocity_setpoint.speed;
speed_body_y_setpoint = 0.f;
}
if (_param_ro_max_thr_speed.get() > FLT_EPSILON) { // Adjust speed setpoints if infeasible
if (_rover_steering_setpoint_sub.updated()) {
_rover_steering_setpoint_sub.copy(&_rover_steering_setpoint);
} else {
_speed_x_setpoint = NAN;
_speed_y_setpoint = NAN;
}
float speed_body_x_setpoint_normalized = math::interpolate<float>(speed_body_x_setpoint,
-_param_ro_max_thr_speed.get(), _param_ro_max_thr_speed.get(), -1.f, 1.f);
_yaw_setpoint = rover_velocity_setpoint.yaw;
}
}
float speed_body_y_setpoint_normalized = math::interpolate<float>(speed_body_y_setpoint,
-_param_ro_max_thr_speed.get(), _param_ro_max_thr_speed.get(), -1.f, 1.f);
const float total_speed = fabsf(speed_body_x_setpoint_normalized) + fabsf(speed_body_y_setpoint_normalized) + fabsf(
_rover_steering_setpoint.normalized_speed_diff);
if (total_speed > 1.f) {
const float theta = atan2f(fabsf(speed_body_y_setpoint_normalized), fabsf(speed_body_x_setpoint_normalized));
const float magnitude = (1.f - fabsf(_rover_steering_setpoint.normalized_speed_diff)) / (sinf(theta) + cosf(theta));
const float normalization = 1.f / (sqrtf(powf(speed_body_x_setpoint_normalized,
2.f) + powf(speed_body_y_setpoint_normalized, 2.f)));
speed_body_x_setpoint_normalized *= magnitude * normalization;
speed_body_y_setpoint_normalized *= magnitude * normalization;
speed_body_x_setpoint = math::interpolate<float>(speed_body_x_setpoint_normalized, -1.f, 1.f,
-_param_ro_max_thr_speed.get(), _param_ro_max_thr_speed.get());
speed_body_y_setpoint = math::interpolate<float>(speed_body_y_setpoint_normalized, -1.f, 1.f,
-_param_ro_max_thr_speed.get(), _param_ro_max_thr_speed.get());
}
Vector2f MecanumVelControl::calcSpeedSetpoint()
{
if (_rover_steering_setpoint_sub.updated()) {
rover_steering_setpoint_s rover_steering_setpoint{};
_rover_steering_setpoint_sub.copy(&rover_steering_setpoint);
_normalized_speed_diff = rover_steering_setpoint.normalized_speed_diff;
}
rover_throttle_setpoint_s rover_throttle_setpoint{};
rover_throttle_setpoint.timestamp = _timestamp;
speed_body_x_setpoint = fabsf(speed_body_x_setpoint) > _param_ro_speed_th.get() ? speed_body_x_setpoint : 0.f;
speed_body_y_setpoint = fabsf(speed_body_y_setpoint) > _param_ro_speed_th.get() ? speed_body_y_setpoint : 0.f;
rover_throttle_setpoint.throttle_body_x = RoverControl::speedControl(_speed_x_setpoint, _pid_speed_x,
speed_body_x_setpoint, _vehicle_speed_body_x, _param_ro_accel_limit.get(), _param_ro_decel_limit.get(),
_param_ro_max_thr_speed.get(), _dt);
rover_throttle_setpoint.throttle_body_y = RoverControl::speedControl(_speed_y_setpoint, _pid_speed_y,
speed_body_y_setpoint, _vehicle_speed_body_y, _param_ro_accel_limit.get(), _param_ro_decel_limit.get(),
_param_ro_max_thr_speed.get(), _dt);
_rover_throttle_setpoint_pub.publish(rover_throttle_setpoint);
float speed_x_setpoint_normalized = math::interpolate<float>(_speed_x_setpoint,
-_param_ro_max_thr_speed.get(), _param_ro_max_thr_speed.get(), -1.f, 1.f);
float speed_y_setpoint_normalized = math::interpolate<float>(_speed_y_setpoint,
-_param_ro_max_thr_speed.get(), _param_ro_max_thr_speed.get(), -1.f, 1.f);
const float total_speed = fabsf(speed_x_setpoint_normalized) + fabsf(speed_y_setpoint_normalized) + fabsf(
_normalized_speed_diff);
Vector2f speed_setpoint = Vector2f(_speed_x_setpoint, _speed_y_setpoint);
if (total_speed > 1.f) {
const float theta = atan2f(fabsf(speed_y_setpoint_normalized), fabsf(speed_x_setpoint_normalized));
const float magnitude = (1.f - fabsf(_normalized_speed_diff)) / (sinf(theta) + cosf(theta));
const float normalization = 1.f / (sqrtf(powf(speed_x_setpoint_normalized,
2.f) + powf(speed_y_setpoint_normalized, 2.f)));
speed_x_setpoint_normalized *= magnitude * normalization;
speed_y_setpoint_normalized *= magnitude * normalization;
speed_setpoint(0) = math::interpolate<float>(speed_x_setpoint_normalized, -1.f, 1.f,
-_param_ro_max_thr_speed.get(), _param_ro_max_thr_speed.get());
speed_setpoint(1) = math::interpolate<float>(speed_y_setpoint_normalized, -1.f, 1.f,
-_param_ro_max_thr_speed.get(), _param_ro_max_thr_speed.get());
}
speed_setpoint(0) = fabsf(speed_setpoint(0)) > _param_ro_speed_th.get() ? speed_setpoint(0) : 0.f;
speed_setpoint(1) = fabsf(speed_setpoint(1)) > _param_ro_speed_th.get() ? speed_setpoint(1) : 0.f;
return speed_setpoint;
}
bool MecanumVelControl::runSanityChecks()
@@ -228,25 +193,18 @@ bool MecanumVelControl::runSanityChecks()
if (_param_ro_speed_limit.get() < FLT_EPSILON) {
ret = false;
if (_prev_param_check_passed) {
events::send<float>(events::ID("mecanum_vel_control_conf_invalid_speed_lim"), events::Log::Error,
"Invalid configuration of necessary parameter RO_SPEED_LIM", _param_ro_speed_limit.get());
}
events::send<float>(events::ID("mecanum_vel_control_conf_invalid_speed_lim"), events::Log::Error,
"Invalid configuration of necessary parameter RO_SPEED_LIM", _param_ro_speed_limit.get());
}
if (_param_ro_max_thr_speed.get() < FLT_EPSILON && _param_ro_speed_p.get() < FLT_EPSILON) {
ret = false;
if (_prev_param_check_passed) {
events::send<float, float>(events::ID("mecanum_vel_control_conf_invalid_speed_control"), events::Log::Error,
"Invalid configuration for speed control: Neither feed forward (RO_MAX_THR_SPEED) nor feedback (RO_SPEED_P) is setup",
_param_ro_max_thr_speed.get(),
_param_ro_speed_p.get());
}
events::send<float, float>(events::ID("mecanum_vel_control_conf_invalid_speed_control"), events::Log::Error,
"Invalid configuration for speed control: Neither feed forward (RO_MAX_THR_SPEED) nor feedback (RO_SPEED_P) is setup",
_param_ro_max_thr_speed.get(),
_param_ro_speed_p.get());
}
_prev_param_check_passed = ret;
return ret;
}
@@ -52,10 +52,7 @@
#include <uORB/topics/rover_velocity_status.h>
#include <uORB/topics/rover_velocity_setpoint.h>
#include <uORB/topics/rover_attitude_setpoint.h>
#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/trajectory_setpoint.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/offboard_control_mode.h>
#include <uORB/topics/vehicle_local_position.h>
using namespace matrix;
@@ -74,10 +71,21 @@ public:
~MecanumVelControl() = default;
/**
* @brief Update velocity controller.
* @brief Generate and publish roverAttitudeSetpoint and RoverThrottleSetpoint from roverVelocitySetpoint.
*/
void updateVelControl();
/**
* @brief Check if the necessary parameters are set.
* @return True if all checks pass.
*/
bool runSanityChecks();
/**
* @brief Reset velocity controller.
*/
void reset() {_pid_speed_x.resetIntegral(); _pid_speed_y.resetIntegral(); _speed_x_setpoint = NAN; _speed_y_setpoint = NAN; _adjusted_speed_x_setpoint.setForcedValue(0.f); _adjusted_speed_y_setpoint.setForcedValue(0.f); _yaw_setpoint = NAN;};
protected:
/**
* @brief Update the parameters of the module.
@@ -91,57 +99,38 @@ private:
void updateSubscriptions();
/**
* @brief Generate and publish roverVelocitySetpoint from velocity of trajectorySetpoint.
* @brief Adjust the speed setpoint if they are infeasible
* @return Speed setpoints
*/
void generateVelocitySetpoint();
/**
* @brief Generate and publish roverAttitudeSetpoint and roverThrottleSetpoint
* from roverVelocitySetpoint.
*/
void generateAttitudeAndThrottleSetpoint();
/**
* @brief Check if the necessary parameters are set.
* @return True if all checks pass.
*/
bool runSanityChecks();
Vector2f calcSpeedSetpoint();
// uORB subscriptions
uORB::Subscription _vehicle_control_mode_sub{ORB_ID(vehicle_control_mode)};
uORB::Subscription _trajectory_setpoint_sub{ORB_ID(trajectory_setpoint)};
uORB::Subscription _offboard_control_mode_sub{ORB_ID(offboard_control_mode)};
uORB::Subscription _vehicle_attitude_sub{ORB_ID(vehicle_attitude)};
uORB::Subscription _vehicle_local_position_sub{ORB_ID(vehicle_local_position)};
uORB::Subscription _rover_velocity_setpoint_sub{ORB_ID(rover_velocity_setpoint)};
uORB::Subscription _rover_attitude_setpoint_sub{ORB_ID(rover_attitude_setpoint)};
uORB::Subscription _rover_steering_setpoint_sub{ORB_ID(rover_steering_setpoint)};
vehicle_control_mode_s _vehicle_control_mode{};
offboard_control_mode_s _offboard_control_mode{};
rover_steering_setpoint_s _rover_steering_setpoint{};
// uORB publications
uORB::Publication<rover_throttle_setpoint_s> _rover_throttle_setpoint_pub{ORB_ID(rover_throttle_setpoint)};
uORB::Publication<rover_attitude_setpoint_s> _rover_attitude_setpoint_pub{ORB_ID(rover_attitude_setpoint)};
uORB::Publication<rover_velocity_status_s> _rover_velocity_status_pub{ORB_ID(rover_velocity_status)};
uORB::Publication<rover_velocity_setpoint_s> _rover_velocity_setpoint_pub{ORB_ID(rover_velocity_setpoint)};
rover_velocity_setpoint_s _rover_velocity_setpoint{};
uORB::Publication<rover_velocity_status_s> _rover_velocity_status_pub{ORB_ID(rover_velocity_status)};
// Variables
hrt_abstime _timestamp{0};
hrt_abstime _last_attitude_setpoint_update{0};
Quatf _vehicle_attitude_quaternion{};
float _vehicle_speed_body_x{0.f};
float _vehicle_speed_body_y{0.f};
float _vehicle_yaw{0.f};
float _dt{0.f};
bool _prev_param_check_passed{false};
float _speed_x_setpoint{NAN};
float _speed_y_setpoint{NAN};
float _normalized_speed_diff{NAN};
float _yaw_setpoint{NAN};
// Controllers
PID _pid_speed_x;
PID _pid_speed_y;
SlewRate<float> _speed_x_setpoint;
SlewRate<float> _speed_y_setpoint;
SlewRate<float> _adjusted_speed_x_setpoint;
SlewRate<float> _adjusted_speed_y_setpoint;
DEFINE_PARAMETERS(
(ParamFloat<px4::params::RO_MAX_THR_SPEED>) _param_ro_max_thr_speed,
+92 -78
View File
@@ -39,8 +39,6 @@ RoverMecanum::RoverMecanum() :
ModuleParams(nullptr),
ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::rate_ctrl)
{
_rover_throttle_setpoint_pub.advertise();
_rover_steering_setpoint_pub.advertise();
updateParams();
}
@@ -53,119 +51,135 @@ bool RoverMecanum::init()
void RoverMecanum::updateParams()
{
ModuleParams::updateParams();
if (_param_ro_accel_limit.get() > FLT_EPSILON && _param_ro_max_thr_speed.get() > FLT_EPSILON) {
_throttle_body_x_setpoint.setSlewRate(_param_ro_accel_limit.get() / _param_ro_max_thr_speed.get());
_throttle_body_y_setpoint.setSlewRate(_param_ro_accel_limit.get() / _param_ro_max_thr_speed.get());
}
}
void RoverMecanum::Run()
{
if (_parameter_update_sub.updated()) {
parameter_update_s param_update{};
_parameter_update_sub.copy(&param_update);
updateParams();
runSanityChecks();
}
const hrt_abstime timestamp_prev = _timestamp;
_timestamp = hrt_absolute_time();
_dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 5000_ms) * 1e-6f;
_mecanum_pos_control.updatePosControl();
_mecanum_vel_control.updateVelControl();
_mecanum_att_control.updateAttControl();
_mecanum_rate_control.updateRateControl();
if (_vehicle_control_mode_sub.updated()) {
_vehicle_control_mode_sub.copy(&_vehicle_control_mode);
vehicle_control_mode_s vehicle_control_mode{};
_vehicle_control_mode_sub.copy(&vehicle_control_mode);
// Run sanity checks if the control mode changes (Note: This has to be done this way, because the topic is periodically updated at 2 Hz)
if (_vehicle_control_mode.flag_control_manual_enabled != vehicle_control_mode.flag_control_manual_enabled ||
_vehicle_control_mode.flag_control_auto_enabled != vehicle_control_mode.flag_control_auto_enabled ||
_vehicle_control_mode.flag_control_offboard_enabled != vehicle_control_mode.flag_control_offboard_enabled ||
_vehicle_control_mode.flag_control_position_enabled != vehicle_control_mode.flag_control_position_enabled ||
_vehicle_control_mode.flag_control_velocity_enabled != vehicle_control_mode.flag_control_velocity_enabled ||
_vehicle_control_mode.flag_control_attitude_enabled != vehicle_control_mode.flag_control_attitude_enabled ||
_vehicle_control_mode.flag_control_rates_enabled != vehicle_control_mode.flag_control_rates_enabled ||
_vehicle_control_mode.flag_control_allocation_enabled != vehicle_control_mode.flag_control_allocation_enabled) {
_vehicle_control_mode = vehicle_control_mode;
runSanityChecks();
reset();
} else {
_vehicle_control_mode = vehicle_control_mode;
}
}
const bool full_manual_mode_enabled = _vehicle_control_mode.flag_control_manual_enabled
&& !_vehicle_control_mode.flag_control_position_enabled && !_vehicle_control_mode.flag_control_attitude_enabled
&& !_vehicle_control_mode.flag_control_rates_enabled;
if (_vehicle_control_mode.flag_armed && _sanity_checks_passed) {
if (full_manual_mode_enabled) { // Manual mode
generateSteeringAndThrottleSetpoint();
}
_was_armed = true;
if (_vehicle_control_mode.flag_armed) {
generateActuatorSetpoint();
// Generate setpoints
if (_vehicle_control_mode.flag_control_manual_enabled) {
manualControl();
} else if (_vehicle_control_mode.flag_control_auto_enabled) {
_auto_mode.autoControl();
} else if (_vehicle_control_mode.flag_control_offboard_enabled) {
_offboard_mode.offboardControl();
}
updateControllers();
} else if (_was_armed) { // Reset all controllers and stop the vehicle
reset();
_mecanum_act_control.stopVehicle();
_was_armed = false;
}
}
void RoverMecanum::generateSteeringAndThrottleSetpoint()
void RoverMecanum::manualControl()
{
manual_control_setpoint_s manual_control_setpoint{};
if (_vehicle_control_mode.flag_control_position_enabled) {
_manual_mode.position();
if (_manual_control_setpoint_sub.update(&manual_control_setpoint)) {
rover_steering_setpoint_s rover_steering_setpoint{};
rover_steering_setpoint.timestamp = _timestamp;
rover_steering_setpoint.normalized_speed_diff = manual_control_setpoint.yaw;
_rover_steering_setpoint_pub.publish(rover_steering_setpoint);
rover_throttle_setpoint_s rover_throttle_setpoint{};
rover_throttle_setpoint.timestamp = _timestamp;
rover_throttle_setpoint.throttle_body_x = manual_control_setpoint.throttle;
rover_throttle_setpoint.throttle_body_y = manual_control_setpoint.roll;
_rover_throttle_setpoint_pub.publish(rover_throttle_setpoint);
} else if (_vehicle_control_mode.flag_control_attitude_enabled) {
_manual_mode.stab();
} else if (_vehicle_control_mode.flag_control_rates_enabled) {
_manual_mode.acro();
} else if (_vehicle_control_mode.flag_control_allocation_enabled) {
_manual_mode.manual();
}
}
void RoverMecanum::generateActuatorSetpoint()
void RoverMecanum::updateControllers()
{
if (_rover_throttle_setpoint_sub.updated()) {
_rover_throttle_setpoint_sub.copy(&_rover_throttle_setpoint);
if (_vehicle_control_mode.flag_control_position_enabled) {
_mecanum_pos_control.updatePosControl();
}
if (_actuator_motors_sub.updated()) {
actuator_motors_s actuator_motors{};
_actuator_motors_sub.copy(&actuator_motors);
_current_throttle_body_x = (actuator_motors.control[0] + actuator_motors.control[1]) / 2.f;
_current_throttle_body_y = (actuator_motors.control[2] - actuator_motors.control[0]) / 2.f;
if (_vehicle_control_mode.flag_control_velocity_enabled) {
_mecanum_vel_control.updateVelControl();
}
if (_rover_steering_setpoint_sub.updated()) {
_rover_steering_setpoint_sub.copy(&_rover_steering_setpoint);
if (_vehicle_control_mode.flag_control_attitude_enabled) {
_mecanum_att_control.updateAttControl();
}
const float throttle_body_x = RoverControl::throttleControl(_throttle_body_x_setpoint,
_rover_throttle_setpoint.throttle_body_x, _current_throttle_body_x, _param_ro_accel_limit.get(),
_param_ro_decel_limit.get(), _param_ro_max_thr_speed.get(), _dt);
const float throttle_body_y = RoverControl::throttleControl(_throttle_body_y_setpoint,
_rover_throttle_setpoint.throttle_body_y, _current_throttle_body_y, _param_ro_accel_limit.get(),
_param_ro_decel_limit.get(), _param_ro_max_thr_speed.get(), _dt);
actuator_motors_s actuator_motors{};
actuator_motors.reversible_flags = _param_r_rev.get();
computeInverseKinematics(throttle_body_x, throttle_body_y,
_rover_steering_setpoint.normalized_speed_diff).copyTo(actuator_motors.control);
actuator_motors.timestamp = _timestamp;
_actuator_motors_pub.publish(actuator_motors);
if (_vehicle_control_mode.flag_control_rates_enabled) {
_mecanum_rate_control.updateRateControl();
}
if (_vehicle_control_mode.flag_control_allocation_enabled) {
_mecanum_act_control.updateActControl();
}
}
Vector4f RoverMecanum::computeInverseKinematics(float throttle_body_x, float throttle_body_y,
const float speed_diff_normalized)
void RoverMecanum::runSanityChecks()
{
const float total_speed = fabsf(throttle_body_x) + fabsf(throttle_body_y) + fabsf(speed_diff_normalized);
if (total_speed > 1.f) { // Adjust speed setpoints if infeasible
const float theta = atan2f(fabsf(throttle_body_y), fabsf(throttle_body_x));
const float magnitude = (1.f - fabsf(speed_diff_normalized)) / (sinf(theta) + cosf(theta));
const float normalization = 1.f / (sqrtf(powf(throttle_body_x, 2.f) + powf(throttle_body_y, 2.f)));
throttle_body_x *= magnitude * normalization;
throttle_body_y *= magnitude * normalization;
if (_vehicle_control_mode.flag_control_rates_enabled && !_mecanum_rate_control.runSanityChecks()) {
_sanity_checks_passed = false;
return;
}
// Calculate motor commands
const float input_data[3] = {throttle_body_x, throttle_body_y, speed_diff_normalized};
const Matrix<float, 3, 1> input(input_data);
const float m_data[12] = {1.f, -1.f, -1.f, 1.f, 1.f, 1.f, 1.f, 1.f, -1.f, 1.f, -1.f, 1.f};
const Matrix<float, 4, 3> m(m_data);
const Vector4f motor_commands = m * input;
if (_vehicle_control_mode.flag_control_attitude_enabled && !_mecanum_att_control.runSanityChecks()) {
_sanity_checks_passed = false;
return;
}
return motor_commands;
if (_vehicle_control_mode.flag_control_velocity_enabled && !_mecanum_vel_control.runSanityChecks()) {
_sanity_checks_passed = false;
return;
}
if (_vehicle_control_mode.flag_control_position_enabled && !_mecanum_pos_control.runSanityChecks()) {
_sanity_checks_passed = false;
return;
}
_sanity_checks_passed = true;
}
void RoverMecanum::reset()
{
_mecanum_vel_control.reset();
_mecanum_att_control.reset();
_mecanum_rate_control.reset();
_manual_mode.reset();
}
int RoverMecanum::task_spawn(int argc, char *argv[])
+32 -51
View File
@@ -40,26 +40,23 @@
#include <px4_platform_common/module_params.h>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
// Libraries
#include <lib/rover_control/RoverControl.hpp>
#include <lib/slew_rate/SlewRate.hpp>
// Library includes
#include <math.h>
// uORB includes
#include <uORB/Subscription.hpp>
#include <uORB/Publication.hpp>
#include <uORB/PublicationMulti.hpp>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/actuator_motors.h>
#include <uORB/topics/rover_steering_setpoint.h>
#include <uORB/topics/rover_throttle_setpoint.h>
#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/manual_control_setpoint.h>
// Local includes
#include "MecanumActControl/MecanumActControl.hpp"
#include "MecanumRateControl/MecanumRateControl.hpp"
#include "MecanumAttControl/MecanumAttControl.hpp"
#include "MecanumVelControl/MecanumVelControl.hpp"
#include "MecanumPosControl/MecanumPosControl.hpp"
#include "MecanumDriveModes/MecanumAutoMode/MecanumAutoMode.hpp"
#include "MecanumDriveModes/MecanumManualMode/MecanumManualMode.hpp"
#include "MecanumDriveModes/MecanumOffboardMode/MecanumOffboardMode.hpp"
class RoverMecanum : public ModuleBase<RoverMecanum>, public ModuleParams,
public px4::ScheduledWorkItem
@@ -92,61 +89,45 @@ private:
void Run() override;
/**
* @brief Generate and publish roverSteeringSetpoint and roverThrottleSetpoint from manualControlSetpoint (Manual Mode).
* @brief Handle manual control
*/
void generateSteeringAndThrottleSetpoint();
void manualControl();
/**
* @brief Generate and publish actuatorMotors setpoints from roverThrottleSetpoint/roverSteeringSetpoint.
* @brief Update the controllers
*/
void generateActuatorSetpoint();
void updateControllers();
/**
* @brief Compute normalized motor commands based on normalized setpoints.
* @param throttle_body_x Normalized speed in body x direction [-1, 1].
* @param throttle_body_y Normalized speed in body y direction [-1, 1].
* @param speed_diff_normalized Speed difference between left and right wheels [-1, 1].
* @return Motor speeds [-1, 1].
* @brief Check proper parameter setup for the controllers
*
* Modifies:
*
* - _sanity_checks_passed: true if checks for all active controllers pass
*/
Vector4f computeInverseKinematics(float throttle_body_x, float throttle_body_y, const float speed_diff_normalized);
void runSanityChecks();
/**
* @brief Reset controllers and manual mode variables.
*/
void reset();
// uORB subscriptions
uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)};
uORB::Subscription _rover_steering_setpoint_sub{ORB_ID(rover_steering_setpoint)};
uORB::Subscription _rover_throttle_setpoint_sub{ORB_ID(rover_throttle_setpoint)};
uORB::Subscription _vehicle_control_mode_sub{ORB_ID(vehicle_control_mode)};
uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)};
uORB::Subscription _actuator_motors_sub{ORB_ID(actuator_motors)};
vehicle_control_mode_s _vehicle_control_mode{};
rover_steering_setpoint_s _rover_steering_setpoint{};
rover_throttle_setpoint_s _rover_throttle_setpoint{};
// uORB publications
uORB::PublicationMulti<actuator_motors_s> _actuator_motors_pub{ORB_ID(actuator_motors)};
uORB::Publication<rover_throttle_setpoint_s> _rover_throttle_setpoint_pub{ORB_ID(rover_throttle_setpoint)};
uORB::Publication<rover_steering_setpoint_s> _rover_steering_setpoint_pub{ORB_ID(rover_steering_setpoint)};
vehicle_control_mode_s _vehicle_control_mode{};
// Class instances
MecanumRateControl _mecanum_rate_control{this};
MecanumAttControl _mecanum_att_control{this};
MecanumVelControl _mecanum_vel_control{this};
MecanumPosControl _mecanum_pos_control{this};
MecanumActControl _mecanum_act_control{this};
MecanumRateControl _mecanum_rate_control{this};
MecanumAttControl _mecanum_att_control{this};
MecanumVelControl _mecanum_vel_control{this};
MecanumPosControl _mecanum_pos_control{this};
MecanumAutoMode _auto_mode{this};
MecanumManualMode _manual_mode{this};
MecanumOffboardMode _offboard_mode{this};
// Variables
hrt_abstime _timestamp{0};
float _dt{0.f};
float _current_throttle_body_x{0.f};
float _current_throttle_body_y{0.f};
// Controllers
SlewRate<float> _throttle_body_x_setpoint{0.f};
SlewRate<float> _throttle_body_y_setpoint{0.f};
// Parameters
DEFINE_PARAMETERS(
(ParamInt<px4::params::CA_R_REV>) _param_r_rev,
(ParamFloat<px4::params::RO_ACCEL_LIM>) _param_ro_accel_limit,
(ParamFloat<px4::params::RO_DECEL_LIM>) _param_ro_decel_limit,
(ParamFloat<px4::params::RO_MAX_THR_SPEED>) _param_ro_max_thr_speed
)
bool _sanity_checks_passed{true}; // True if checks for all active controllers pass
bool _was_armed{false}; // True if the vehicle was armed before the last reset
};