mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
Merge branch 'feat/safe_dds' of github.com:PX4/PX4-Autopilot into feat/safe_dds
This commit is contained in:
commit
695e2c7caa
@ -150,7 +150,6 @@ Checks: '*,
|
||||
-readability-convert-member-functions-to-static,
|
||||
-readability-make-member-function-const,
|
||||
-bugprone-implicit-widening-of-multiplication-result,
|
||||
-bugprone-macro-parentheses,
|
||||
-bugprone-multi-level-implicit-pointer-conversion,
|
||||
-bugprone-signed-char-misuse,
|
||||
-cppcoreguidelines-avoid-non-const-global-variables,
|
||||
|
||||
@ -16,7 +16,13 @@ git checkout -b mydescriptivebranchname
|
||||
|
||||
## Edit and build the code
|
||||
|
||||
The [developer guide](https://docs.px4.io/main/en/development/development.html) explains how to set up the development environment on Mac OS, Linux or Windows. Please take note of our [coding style](https://docs.px4.io/main/en/contribute/code.html) when editing files.
|
||||
The [developer guide](https://docs.px4.io/main/en/development/development.html) explains how to set up the development environment on Mac OS, Linux or Windows.
|
||||
|
||||
### Coding standards
|
||||
|
||||
All C/C++ code must follow the [PX4 coding style](https://docs.px4.io/main/en/contribute/code.html). Formatting is enforced by [astyle](http://astyle.sourceforge.net/) in CI (`make check_format`). Code quality checks run via [clang-tidy](https://clang.llvm.org/extra/clang-tidy/). Pull requests that fail either check will not be merged.
|
||||
|
||||
Python code is checked with [mypy](https://mypy-lang.org/) and [flake8](https://flake8.pycqa.org/).
|
||||
|
||||
## Commit message convention
|
||||
|
||||
@ -141,6 +147,20 @@ git push --force-with-lease
|
||||
|
||||
## Test your changes
|
||||
|
||||
PX4 is safety-critical software. All contributions must include adequate testing where practical:
|
||||
|
||||
- **New features** must include unit tests and/or integration tests that exercise the new functionality, where practical. Hardware-dependent changes that cannot be tested in SITL should include bench test or flight test evidence.
|
||||
- **Bug fixes** must include a regression test where practical. When automated testing is not feasible (hardware-specific issues, race conditions, etc.), provide a link to a flight log demonstrating the fix and the reproduction steps for the original bug.
|
||||
- **Reviewers** will verify that tests or test evidence exist before approving a pull request.
|
||||
|
||||
### Types of tests
|
||||
|
||||
| Test type | When to use | How to run |
|
||||
|-----------|-------------|------------|
|
||||
| **Unit tests** (gtest) | Module-level logic, math, parsing | `make tests` |
|
||||
| **SITL integration tests** (MAVSDK) | Flight behavior, failsafes, missions | `test/mavsdk_tests/` |
|
||||
| **Bench tests / flight logs** | Hardware-dependent changes | Upload logs to [Flight Review](https://logs.px4.io) |
|
||||
|
||||
Since we care about safety, we will regularly ask you for test results. Best is to do a test flight (or bench test where it applies) and upload the log file from it (on the microSD card in the logs directory) to Google Drive or Dropbox and share the link.
|
||||
|
||||
## Push your changes
|
||||
|
||||
40
SECURITY.md
40
SECURITY.md
@ -2,24 +2,40 @@
|
||||
|
||||
## Supported Versions
|
||||
|
||||
The following is a list of versions the development team is currently supporting.
|
||||
The following versions receive security updates:
|
||||
|
||||
| Version | Supported |
|
||||
| ------- | ------------------ |
|
||||
| 1.4.x | :white_check_mark: |
|
||||
| 1.3.3 | :white_check_mark: |
|
||||
| < 1.3 | :x: |
|
||||
| 1.16.x | :white_check_mark: |
|
||||
| < 1.16 | :x: |
|
||||
|
||||
## Reporting a Vulnerability
|
||||
|
||||
We currently only receive security vulnerability reports through GitHub.
|
||||
We receive security vulnerability reports through GitHub Security Advisories.
|
||||
|
||||
To begin a report, please go to the top-level repository, for example, PX4/PX4-Autopilot,
|
||||
and click on the Security tab. If you are on mobile, click the ... dropdown menu, and then click Security.
|
||||
To begin a report, go to the [PX4/PX4-Autopilot](https://github.com/PX4/PX4-Autopilot) repository
|
||||
and click on the **Security** tab. If you are on mobile, click the **...** dropdown menu, then click **Security**.
|
||||
|
||||
Click Report a Vulnerability to open the advisory form. Fill in the advisory details form.
|
||||
Make sure your title is descriptive, and the development team can find all of the relevant details needed
|
||||
to verify on the description box. We recommend you add as much data as possible. We welcome logs,
|
||||
screenshots, photos, and videos, anything that can help us verify and identify the issues being reported.
|
||||
Click **Report a Vulnerability** to open the advisory form. Fill in the advisory details form.
|
||||
Make sure your title is descriptive and the description contains all relevant details needed
|
||||
to verify the issue. We welcome logs, screenshots, photos, and videos.
|
||||
|
||||
At the bottom of the form, click Submit report. The maintainer team will be notified and will get back to you ASAP.
|
||||
At the bottom of the form, click **Submit report**.
|
||||
|
||||
## Response Process
|
||||
|
||||
1. **Acknowledgment**: The maintainer team will acknowledge your report within **7 days**.
|
||||
2. **Triage**: We will assess severity and impact and communicate next steps.
|
||||
3. **Disclosure**: We coordinate disclosure with the reporter. We follow responsible disclosure practices and will credit reporters in the advisory unless they request anonymity.
|
||||
|
||||
If you do not receive acknowledgment within 7 days, please follow up by emailing the [release managers](MAINTAINERS.md).
|
||||
|
||||
## Secure Development Practices
|
||||
|
||||
The PX4 development team applies the following practices to reduce security risk:
|
||||
|
||||
- **Code review**: All changes require peer review before merging.
|
||||
- **Static analysis**: [clang-tidy](https://clang.llvm.org/extra/clang-tidy/) runs on every pull request with warnings treated as errors.
|
||||
- **Fuzzing**: A daily fuzzing pipeline using [Google fuzztest](https://github.com/google/fuzztest) tests MAVLink message handling and GNSS driver protocol parsing.
|
||||
- **Input validation**: All external inputs (MAVLink messages, RC signals, sensor data) are validated against expected ranges before use.
|
||||
- **Compiler hardening**: Builds use `-Wall -Werror`, stack protectors, and other hardening flags where supported by the target platform.
|
||||
|
||||
@ -759,6 +759,7 @@
|
||||
- [Receiving Messages](mavlink/receiving_messages.md)
|
||||
- [Custom MAVLink Messages](mavlink/custom_messages.md)
|
||||
- [Message Signing](mavlink/message_signing.md)
|
||||
- [Security Hardening](mavlink/security_hardening.md)
|
||||
- [Protocols/Microservices](mavlink/protocols.md)
|
||||
- [Standard Modes Protocol](mavlink/standard_modes.md)
|
||||
- [uXRCE-DDS (PX4-ROS 2/DDS Bridge)](middleware/uxrce_dds.md)
|
||||
|
||||
@ -20502,7 +20502,8 @@ Measurement noise for magnetic heading fusion.
|
||||
|
||||
Determines the reference source of height data used by the EKF.
|
||||
|
||||
When multiple height sources are enabled at the same time, the height estimate will always converge towards the reference height source selected by this parameter. The range sensor and vision options should only be used when for operation over a flat surface as the local NED origin will move up and down with ground level. If GPS is set as reference but altitude fusion is disabled in EKF2_GPS_CTRL, the GPS altitude is still used to initiaize the bias of the other height sensors.
|
||||
When multiple height sources are enabled at the same time, the height estimate will always converge towards the reference height source selected by this parameter. The range sensor and vision options should only be used when for operation over a flat surface as the local NED origin will move up and down with ground level.
|
||||
If GPS is set as reference and EKF2_GPS_CTRL is not 0, the GPS altitude is still used to initiaize the bias of the other height sensors, regardless of the altitude fusion bit in EKF2_GPS_CTRL.
|
||||
|
||||
**Values:**
|
||||
|
||||
|
||||
@ -14,6 +14,10 @@ It also links instructions for how you can add PX4 support for:
|
||||
- [Message Signing](../mavlink/message_signing.md)
|
||||
- [Protocols/Microservices](../mavlink/protocols.md)
|
||||
|
||||
::: warning
|
||||
MAVLink messages are unauthenticated by default. Without [message signing](../mavlink/message_signing.md) enabled, any device that can send MAVLink messages to the vehicle can execute commands including shell access, file operations, and flight termination. Production deployments must enable signing and follow the [Security Hardening](../mavlink/security_hardening.md) guide.
|
||||
:::
|
||||
|
||||
::: info
|
||||
We do not yet cover _command_ handling and sending, or how to implement your own microservices.
|
||||
:::
|
||||
|
||||
84
docs/en/mavlink/security_hardening.md
Normal file
84
docs/en/mavlink/security_hardening.md
Normal file
@ -0,0 +1,84 @@
|
||||
# MAVLink Security Hardening for Production Deployments
|
||||
|
||||
<Badge type="tip" text="PX4 v1.17" />
|
||||
|
||||
MAVLink is an open communication protocol designed for lightweight, low-latency communication between drones and ground stations.
|
||||
By default, all MAVLink messages are unauthenticated.
|
||||
This is intentional for development and testing, but **production deployments must enable [message signing](message_signing.md)** to prevent unauthorized access.
|
||||
|
||||
::: warning
|
||||
Without message signing enabled, any device that can send MAVLink messages to the vehicle (via radio, network, or serial) can execute any command, including shell access, file operations, parameter changes, mission uploads, arming, and flight termination.
|
||||
:::
|
||||
|
||||
## What Is at Risk
|
||||
|
||||
When MAVLink signing is not enabled, an attacker within communication range can:
|
||||
|
||||
| Capability | MAVLink mechanism |
|
||||
| ---------------------------- | ------------------------------------------------ |
|
||||
| Execute shell commands | `SERIAL_CONTROL` with `SERIAL_CONTROL_DEV_SHELL` |
|
||||
| Read, write, or delete files | MAVLink FTP protocol |
|
||||
| Change any flight parameter | `PARAM_SET` / `PARAM_EXT_SET` |
|
||||
| Upload or overwrite missions | Mission protocol |
|
||||
| Arm or disarm motors | `MAV_CMD_COMPONENT_ARM_DISARM` |
|
||||
| Terminate flight (crash) | `MAV_CMD_DO_FLIGHTTERMINATION` |
|
||||
| Trigger emergency landing | Spoofed `BATTERY_STATUS` |
|
||||
| Reboot the vehicle | `MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN` |
|
||||
|
||||
All of these are standard MAVLink capabilities used by ground control stations.
|
||||
Without signing, there is no distinction between a legitimate GCS and an unauthorized sender.
|
||||
|
||||
## Hardening Checklist
|
||||
|
||||
### 1. Enable Message Signing
|
||||
|
||||
Message signing provides cryptographic authentication for all MAVLink communication.
|
||||
See [Message Signing](message_signing.md) for full details.
|
||||
|
||||
Steps:
|
||||
|
||||
1. Connect the vehicle via **USB** (key provisioning only works over USB).
|
||||
2. Provision a 32-byte secret key using the [SETUP_SIGNING](https://mavlink.io/en/messages/common.html#SETUP_SIGNING) message.
|
||||
3. Set [MAV_SIGN_CFG](../advanced_config/parameter_reference.md#MAV_SIGN_CFG) to **1** (signing enabled on all links except USB) or **2** (signing on all links including USB).
|
||||
4. Provision the same key on all ground control stations and companion computers that need to communicate with the vehicle.
|
||||
5. Verify that unsigned messages from unknown sources are rejected.
|
||||
|
||||
::: info
|
||||
`MAV_SIGN_CFG=1` is recommended for most deployments.
|
||||
This enforces signing on telemetry radios and network links while allowing unsigned access over USB for maintenance.
|
||||
USB connections require physical access to the vehicle, which provides equivalent security to physical key access.
|
||||
:::
|
||||
|
||||
### 2. Secure Physical Access
|
||||
|
||||
- Protect access to the SD card. The signing key is stored at `/mavlink/mavlink-signing-key.bin` and can be read or removed by anyone with physical access.
|
||||
- USB connections bypass signing when `MAV_SIGN_CFG=1`. Ensure USB ports are not exposed in deployed configurations.
|
||||
|
||||
### 3. Secure Network Links
|
||||
|
||||
- Do not expose MAVLink UDP/TCP ports to untrusted networks or the internet.
|
||||
- Place MAVLink communication links behind firewalls or VPNs.
|
||||
- Segment MAVLink networks from business or public networks.
|
||||
- When using companion computers, audit which network interfaces MAVLink is bound to.
|
||||
|
||||
### 4. Understand the Limitations
|
||||
|
||||
- **No encryption**: Message signing provides authentication and integrity, but messages are sent in plaintext. An eavesdropper can read telemetry and commands but cannot forge them.
|
||||
- **Allowlisted messages**: A small set of [safety-critical messages](message_signing.md#unsigned-message-allowlist) (RADIO_STATUS, ADSB_VEHICLE, COLLISION) are always accepted unsigned.
|
||||
- **Key management**: There is no automatic key rotation. Keys must be reprovisioned manually via USB if compromised.
|
||||
|
||||
## Integrator Responsibility
|
||||
|
||||
PX4 is open-source flight controller firmware used by manufacturers and system integrators to build commercial and custom drone platforms.
|
||||
|
||||
Securing the communication links for a specific deployment is the responsibility of the system integrator.
|
||||
This includes:
|
||||
|
||||
- Choosing appropriate radio hardware and link security
|
||||
- Enabling and managing MAVLink message signing
|
||||
- Restricting network access to MAVLink interfaces
|
||||
- Applying firmware updates that address security issues
|
||||
- Evaluating whether the default configuration meets the security requirements of the target application
|
||||
|
||||
PX4 provides the tools for securing MAVLink communication.
|
||||
Integrators must enable and configure them for their deployment context.
|
||||
@ -95,202 +95,202 @@ They are not build into the module, and hence are neither published or subscribe
|
||||
|
||||
::: details See messages
|
||||
|
||||
- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md)
|
||||
- [SensorAirflow](../msg_docs/SensorAirflow.md)
|
||||
- [UlogStream](../msg_docs/UlogStream.md)
|
||||
- [GeneratorStatus](../msg_docs/GeneratorStatus.md)
|
||||
- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md)
|
||||
- [ParameterUpdate](../msg_docs/ParameterUpdate.md)
|
||||
- [OrbTestLarge](../msg_docs/OrbTestLarge.md)
|
||||
- [EstimatorStates](../msg_docs/EstimatorStates.md)
|
||||
- [CellularStatus](../msg_docs/CellularStatus.md)
|
||||
- [DatamanResponse](../msg_docs/DatamanResponse.md)
|
||||
- [AirspeedWind](../msg_docs/AirspeedWind.md)
|
||||
- [QshellReq](../msg_docs/QshellReq.md)
|
||||
- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md)
|
||||
- [TuneControl](../msg_docs/TuneControl.md)
|
||||
- [VehicleRoi](../msg_docs/VehicleRoi.md)
|
||||
- [UlogStreamAck](../msg_docs/UlogStreamAck.md)
|
||||
- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md)
|
||||
- [ActuatorArmed](../msg_docs/ActuatorArmed.md)
|
||||
- [EventV0](../msg_docs/EventV0.md)
|
||||
- [GeofenceResult](../msg_docs/GeofenceResult.md)
|
||||
- [HomePositionV0](../msg_docs/HomePositionV0.md)
|
||||
- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md)
|
||||
- [MagWorkerData](../msg_docs/MagWorkerData.md)
|
||||
- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md)
|
||||
- [HeaterStatus](../msg_docs/HeaterStatus.md)
|
||||
- [EstimatorBias](../msg_docs/EstimatorBias.md)
|
||||
- [FigureEightStatus](../msg_docs/FigureEightStatus.md)
|
||||
- [MissionResult](../msg_docs/MissionResult.md)
|
||||
- [GpioOut](../msg_docs/GpioOut.md)
|
||||
- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md)
|
||||
- [TakeoffStatus](../msg_docs/TakeoffStatus.md)
|
||||
- [SensorMag](../msg_docs/SensorMag.md)
|
||||
- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md)
|
||||
- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md)
|
||||
- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md)
|
||||
- [Ping](../msg_docs/Ping.md)
|
||||
- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md)
|
||||
- [ActuatorTest](../msg_docs/ActuatorTest.md)
|
||||
- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md)
|
||||
- [PpsCapture](../msg_docs/PpsCapture.md)
|
||||
- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md)
|
||||
- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md)
|
||||
- [LandingTargetPose](../msg_docs/LandingTargetPose.md)
|
||||
- [DeviceInformation](../msg_docs/DeviceInformation.md)
|
||||
- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md)
|
||||
- [Mission](../msg_docs/Mission.md)
|
||||
- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md)
|
||||
- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md)
|
||||
- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md)
|
||||
- [LedControl](../msg_docs/LedControl.md)
|
||||
- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md)
|
||||
- [LoggerStatus](../msg_docs/LoggerStatus.md)
|
||||
- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md)
|
||||
- [DebugVect](../msg_docs/DebugVect.md)
|
||||
- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md)
|
||||
- [PowerButtonState](../msg_docs/PowerButtonState.md)
|
||||
- [GpsInjectData](../msg_docs/GpsInjectData.md)
|
||||
- [EscReport](../msg_docs/EscReport.md)
|
||||
- [AirspeedWind](../msg_docs/AirspeedWind.md)
|
||||
- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md)
|
||||
- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md)
|
||||
- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md)
|
||||
- [EscStatus](../msg_docs/EscStatus.md)
|
||||
- [TaskStackInfo](../msg_docs/TaskStackInfo.md)
|
||||
- [MountOrientation](../msg_docs/MountOrientation.md)
|
||||
- [Cpuload](../msg_docs/Cpuload.md)
|
||||
- [RaptorStatus](../msg_docs/RaptorStatus.md)
|
||||
- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md)
|
||||
- [MavlinkLog](../msg_docs/MavlinkLog.md)
|
||||
- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md)
|
||||
- [GainCompression](../msg_docs/GainCompression.md)
|
||||
- [ActuatorTest](../msg_docs/ActuatorTest.md)
|
||||
- [ButtonEvent](../msg_docs/ButtonEvent.md)
|
||||
- [HeaterStatus](../msg_docs/HeaterStatus.md)
|
||||
- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md)
|
||||
- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md)
|
||||
- [GeneratorStatus](../msg_docs/GeneratorStatus.md)
|
||||
- [OrbTest](../msg_docs/OrbTest.md)
|
||||
- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md)
|
||||
- [FollowTarget](../msg_docs/FollowTarget.md)
|
||||
- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md)
|
||||
- [QshellReq](../msg_docs/QshellReq.md)
|
||||
- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md)
|
||||
- [TecsStatus](../msg_docs/TecsStatus.md)
|
||||
- [Vtx](../msg_docs/Vtx.md)
|
||||
- [SensorGyro](../msg_docs/SensorGyro.md)
|
||||
- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md)
|
||||
- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md)
|
||||
- [GpioIn](../msg_docs/GpioIn.md)
|
||||
- [DatamanResponse](../msg_docs/DatamanResponse.md)
|
||||
- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md)
|
||||
- [GimbalControls](../msg_docs/GimbalControls.md)
|
||||
- [TakeoffStatus](../msg_docs/TakeoffStatus.md)
|
||||
- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md)
|
||||
- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md)
|
||||
- [SensorMag](../msg_docs/SensorMag.md)
|
||||
- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md)
|
||||
- [VehicleCommandAckV0](../msg_docs/VehicleCommandAckV0.md)
|
||||
- [QshellRetval](../msg_docs/QshellRetval.md)
|
||||
- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md)
|
||||
- [RcChannels](../msg_docs/RcChannels.md)
|
||||
- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md)
|
||||
- [RtlStatus](../msg_docs/RtlStatus.md)
|
||||
- [OrbTestMedium](../msg_docs/OrbTestMedium.md)
|
||||
- [Rpm](../msg_docs/Rpm.md)
|
||||
- [PwmInput](../msg_docs/PwmInput.md)
|
||||
- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md)
|
||||
- [SensorUwb](../msg_docs/SensorUwb.md)
|
||||
- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md)
|
||||
- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md)
|
||||
- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md)
|
||||
- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md)
|
||||
- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md)
|
||||
- [OrbTestLarge](../msg_docs/OrbTestLarge.md)
|
||||
- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md)
|
||||
- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md)
|
||||
- [GpioRequest](../msg_docs/GpioRequest.md)
|
||||
- [DebugValue](../msg_docs/DebugValue.md)
|
||||
- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md)
|
||||
- [VelocityLimits](../msg_docs/VelocityLimits.md)
|
||||
- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md)
|
||||
- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md)
|
||||
- [SatelliteInfo](../msg_docs/SatelliteInfo.md)
|
||||
- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md)
|
||||
- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md)
|
||||
- [LedControl](../msg_docs/LedControl.md)
|
||||
- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md)
|
||||
- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md)
|
||||
- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md)
|
||||
- [MountOrientation](../msg_docs/MountOrientation.md)
|
||||
- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md)
|
||||
- [VehicleStatusV1](../msg_docs/VehicleStatusV1.md)
|
||||
- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md)
|
||||
- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md)
|
||||
- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md)
|
||||
- [RtlStatus](../msg_docs/RtlStatus.md)
|
||||
- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md)
|
||||
- [OrbTest](../msg_docs/OrbTest.md)
|
||||
- [EstimatorStatus](../msg_docs/EstimatorStatus.md)
|
||||
- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md)
|
||||
- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md)
|
||||
- [SensorGyro](../msg_docs/SensorGyro.md)
|
||||
- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md)
|
||||
- [BatteryInfo](../msg_docs/BatteryInfo.md)
|
||||
- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md)
|
||||
- [VehicleCommandAckV0](../msg_docs/VehicleCommandAckV0.md)
|
||||
- [SensorUwb](../msg_docs/SensorUwb.md)
|
||||
- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md)
|
||||
- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md)
|
||||
- [OrbitStatus](../msg_docs/OrbitStatus.md)
|
||||
- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md)
|
||||
- [SensorCorrection](../msg_docs/SensorCorrection.md)
|
||||
- [Mission](../msg_docs/Mission.md)
|
||||
- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md)
|
||||
- [GpioRequest](../msg_docs/GpioRequest.md)
|
||||
- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md)
|
||||
- [SensorBaro](../msg_docs/SensorBaro.md)
|
||||
- [SensorAccel](../msg_docs/SensorAccel.md)
|
||||
- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md)
|
||||
- [BatteryInfo](../msg_docs/BatteryInfo.md)
|
||||
- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md)
|
||||
- [GpioOut](../msg_docs/GpioOut.md)
|
||||
- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md)
|
||||
- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md)
|
||||
- [Gripper](../msg_docs/Gripper.md)
|
||||
- [IrlockReport](../msg_docs/IrlockReport.md)
|
||||
- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md)
|
||||
- [Airspeed](../msg_docs/Airspeed.md)
|
||||
- [Event](../msg_docs/Event.md)
|
||||
- [PwmInput](../msg_docs/PwmInput.md)
|
||||
- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md)
|
||||
- [Cpuload](../msg_docs/Cpuload.md)
|
||||
- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md)
|
||||
- [RcChannels](../msg_docs/RcChannels.md)
|
||||
- [VehicleAirData](../msg_docs/VehicleAirData.md)
|
||||
- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md)
|
||||
- [VehicleImu](../msg_docs/VehicleImu.md)
|
||||
- [ButtonEvent](../msg_docs/ButtonEvent.md)
|
||||
- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md)
|
||||
- [SensorHygrometer](../msg_docs/SensorHygrometer.md)
|
||||
- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md)
|
||||
- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md)
|
||||
- [GainCompression](../msg_docs/GainCompression.md)
|
||||
- [ActionRequest](../msg_docs/ActionRequest.md)
|
||||
- [VehicleGlobalPositionV0](../msg_docs/VehicleGlobalPositionV0.md)
|
||||
- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md)
|
||||
- [GpioConfig](../msg_docs/GpioConfig.md)
|
||||
- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md)
|
||||
- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md)
|
||||
- [HealthReport](../msg_docs/HealthReport.md)
|
||||
- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md)
|
||||
- [GeofenceStatus](../msg_docs/GeofenceStatus.md)
|
||||
- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md)
|
||||
- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md)
|
||||
- [DatamanRequest](../msg_docs/DatamanRequest.md)
|
||||
- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md)
|
||||
- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md)
|
||||
- [MavlinkLog](../msg_docs/MavlinkLog.md)
|
||||
- [CameraCapture](../msg_docs/CameraCapture.md)
|
||||
- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md)
|
||||
- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md)
|
||||
- [EscReport](../msg_docs/EscReport.md)
|
||||
- [VehicleConstraints](../msg_docs/VehicleConstraints.md)
|
||||
- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md)
|
||||
- [DebugKeyValue](../msg_docs/DebugKeyValue.md)
|
||||
- [DebugValue](../msg_docs/DebugValue.md)
|
||||
- [GpioIn](../msg_docs/GpioIn.md)
|
||||
- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md)
|
||||
- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md)
|
||||
- [LandingTargetPose](../msg_docs/LandingTargetPose.md)
|
||||
- [Px4ioStatus](../msg_docs/Px4ioStatus.md)
|
||||
- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md)
|
||||
- [GpsDump](../msg_docs/GpsDump.md)
|
||||
- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md)
|
||||
- [SystemPower](../msg_docs/SystemPower.md)
|
||||
- [NeuralControl](../msg_docs/NeuralControl.md)
|
||||
- [LandingGearWheel](../msg_docs/LandingGearWheel.md)
|
||||
- [SensorTemp](../msg_docs/SensorTemp.md)
|
||||
- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md)
|
||||
- [TecsStatus](../msg_docs/TecsStatus.md)
|
||||
- [WheelEncoders](../msg_docs/WheelEncoders.md)
|
||||
- [RadioStatus](../msg_docs/RadioStatus.md)
|
||||
- [RoverRateStatus](../msg_docs/RoverRateStatus.md)
|
||||
- [FuelTankStatus](../msg_docs/FuelTankStatus.md)
|
||||
- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md)
|
||||
- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md)
|
||||
- [FollowTarget](../msg_docs/FollowTarget.md)
|
||||
- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md)
|
||||
- [GimbalControls](../msg_docs/GimbalControls.md)
|
||||
- [RaptorStatus](../msg_docs/RaptorStatus.md)
|
||||
- [SensorGyroFft](../msg_docs/SensorGyroFft.md)
|
||||
- [SensorsStatus](../msg_docs/SensorsStatus.md)
|
||||
- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md)
|
||||
- [OrbTestMedium](../msg_docs/OrbTestMedium.md)
|
||||
- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md)
|
||||
- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md)
|
||||
- [InputRc](../msg_docs/InputRc.md)
|
||||
- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md)
|
||||
- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md)
|
||||
- [PositionSetpoint](../msg_docs/PositionSetpoint.md)
|
||||
- [DeviceInformation](../msg_docs/DeviceInformation.md)
|
||||
- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md)
|
||||
- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md)
|
||||
- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md)
|
||||
- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md)
|
||||
- [QshellRetval](../msg_docs/QshellRetval.md)
|
||||
- [AdcReport](../msg_docs/AdcReport.md)
|
||||
- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md)
|
||||
- [CameraTrigger](../msg_docs/CameraTrigger.md)
|
||||
- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md)
|
||||
- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md)
|
||||
- [PowerMonitor](../msg_docs/PowerMonitor.md)
|
||||
- [RcParameterMap](../msg_docs/RcParameterMap.md)
|
||||
- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md)
|
||||
- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md)
|
||||
- [SensorSelection](../msg_docs/SensorSelection.md)
|
||||
- [Vtx](../msg_docs/Vtx.md)
|
||||
- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md)
|
||||
- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md)
|
||||
- [DebugArray](../msg_docs/DebugArray.md)
|
||||
- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md)
|
||||
- [TaskStackInfo](../msg_docs/TaskStackInfo.md)
|
||||
- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md)
|
||||
- [DebugVect](../msg_docs/DebugVect.md)
|
||||
- [RaptorInput](../msg_docs/RaptorInput.md)
|
||||
- [DifferentialPressure](../msg_docs/DifferentialPressure.md)
|
||||
- [EscStatus](../msg_docs/EscStatus.md)
|
||||
- [LoggerStatus](../msg_docs/LoggerStatus.md)
|
||||
- [Rpm](../msg_docs/Rpm.md)
|
||||
- [LogMessage](../msg_docs/LogMessage.md)
|
||||
- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md)
|
||||
- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md)
|
||||
- [CameraStatus](../msg_docs/CameraStatus.md)
|
||||
- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md)
|
||||
- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md)
|
||||
- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md)
|
||||
- [MissionResult](../msg_docs/MissionResult.md)
|
||||
- [TuneControl](../msg_docs/TuneControl.md)
|
||||
- [WheelEncoders](../msg_docs/WheelEncoders.md)
|
||||
- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md)
|
||||
- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md)
|
||||
- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md)
|
||||
- [HealthReport](../msg_docs/HealthReport.md)
|
||||
- [NavigatorStatus](../msg_docs/NavigatorStatus.md)
|
||||
- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md)
|
||||
- [CellularStatus](../msg_docs/CellularStatus.md)
|
||||
- [LandingGearWheel](../msg_docs/LandingGearWheel.md)
|
||||
- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md)
|
||||
- [SensorGyroFft](../msg_docs/SensorGyroFft.md)
|
||||
- [VehicleRoi](../msg_docs/VehicleRoi.md)
|
||||
- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md)
|
||||
- [PpsCapture](../msg_docs/PpsCapture.md)
|
||||
- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md)
|
||||
- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md)
|
||||
- [ActuatorArmed](../msg_docs/ActuatorArmed.md)
|
||||
- [DifferentialPressure](../msg_docs/DifferentialPressure.md)
|
||||
- [ParameterUpdate](../msg_docs/ParameterUpdate.md)
|
||||
- [ActionRequest](../msg_docs/ActionRequest.md)
|
||||
- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md)
|
||||
- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md)
|
||||
- [DebugArray](../msg_docs/DebugArray.md)
|
||||
- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md)
|
||||
- [RoverRateStatus](../msg_docs/RoverRateStatus.md)
|
||||
- [SatelliteInfo](../msg_docs/SatelliteInfo.md)
|
||||
- [CameraStatus](../msg_docs/CameraStatus.md)
|
||||
- [LogMessage](../msg_docs/LogMessage.md)
|
||||
- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md)
|
||||
- [SensorBaro](../msg_docs/SensorBaro.md)
|
||||
- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md)
|
||||
- [SensorHygrometer](../msg_docs/SensorHygrometer.md)
|
||||
- [PositionSetpoint](../msg_docs/PositionSetpoint.md)
|
||||
- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md)
|
||||
- [GpsDump](../msg_docs/GpsDump.md)
|
||||
- [GpioConfig](../msg_docs/GpioConfig.md)
|
||||
- [GeofenceStatus](../msg_docs/GeofenceStatus.md)
|
||||
- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md)
|
||||
- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md)
|
||||
- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md)
|
||||
- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md)
|
||||
- [GeofenceResult](../msg_docs/GeofenceResult.md)
|
||||
- [EstimatorBias](../msg_docs/EstimatorBias.md)
|
||||
- [SystemPower](../msg_docs/SystemPower.md)
|
||||
- [EventV0](../msg_docs/EventV0.md)
|
||||
- [CameraCapture](../msg_docs/CameraCapture.md)
|
||||
- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md)
|
||||
- [HomePositionV0](../msg_docs/HomePositionV0.md)
|
||||
- [VehicleGlobalPositionV0](../msg_docs/VehicleGlobalPositionV0.md)
|
||||
- [Px4ioStatus](../msg_docs/Px4ioStatus.md)
|
||||
- [EstimatorStates](../msg_docs/EstimatorStates.md)
|
||||
- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md)
|
||||
- [FigureEightStatus](../msg_docs/FigureEightStatus.md)
|
||||
- [InputRc](../msg_docs/InputRc.md)
|
||||
- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md)
|
||||
- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md)
|
||||
- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md)
|
||||
- [DatamanRequest](../msg_docs/DatamanRequest.md)
|
||||
- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md)
|
||||
- [VehicleConstraints](../msg_docs/VehicleConstraints.md)
|
||||
- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md)
|
||||
- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md)
|
||||
- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md)
|
||||
- [NeuralControl](../msg_docs/NeuralControl.md)
|
||||
- [DebugKeyValue](../msg_docs/DebugKeyValue.md)
|
||||
- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md)
|
||||
- [EstimatorStatus](../msg_docs/EstimatorStatus.md)
|
||||
- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md)
|
||||
- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md)
|
||||
- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md)
|
||||
- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md)
|
||||
- [CameraTrigger](../msg_docs/CameraTrigger.md)
|
||||
- [PowerButtonState](../msg_docs/PowerButtonState.md)
|
||||
- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md)
|
||||
- [VehicleStatusV1](../msg_docs/VehicleStatusV1.md)
|
||||
- [AdcReport](../msg_docs/AdcReport.md)
|
||||
- [SensorsStatus](../msg_docs/SensorsStatus.md)
|
||||
- [UlogStreamAck](../msg_docs/UlogStreamAck.md)
|
||||
- [UlogStream](../msg_docs/UlogStream.md)
|
||||
- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md)
|
||||
- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md)
|
||||
- [SensorAccel](../msg_docs/SensorAccel.md)
|
||||
- [PowerMonitor](../msg_docs/PowerMonitor.md)
|
||||
- [OrbitStatus](../msg_docs/OrbitStatus.md)
|
||||
- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md)
|
||||
- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md)
|
||||
- [Airspeed](../msg_docs/Airspeed.md)
|
||||
- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md)
|
||||
- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md)
|
||||
- [RadioStatus](../msg_docs/RadioStatus.md)
|
||||
- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md)
|
||||
- [VehicleAirData](../msg_docs/VehicleAirData.md)
|
||||
- [SensorAirflow](../msg_docs/SensorAirflow.md)
|
||||
- [Ping](../msg_docs/Ping.md)
|
||||
- [MagWorkerData](../msg_docs/MagWorkerData.md)
|
||||
- [FuelTankStatus](../msg_docs/FuelTankStatus.md)
|
||||
- [GpsInjectData](../msg_docs/GpsInjectData.md)
|
||||
- [Event](../msg_docs/Event.md)
|
||||
- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md)
|
||||
- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md)
|
||||
- [RcParameterMap](../msg_docs/RcParameterMap.md)
|
||||
- [Gripper](../msg_docs/Gripper.md)
|
||||
- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md)
|
||||
- [VehicleImu](../msg_docs/VehicleImu.md)
|
||||
- [SensorSelection](../msg_docs/SensorSelection.md)
|
||||
- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md)
|
||||
- [IrlockReport](../msg_docs/IrlockReport.md)
|
||||
- [SensorTemp](../msg_docs/SensorTemp.md)
|
||||
- [RaptorInput](../msg_docs/RaptorInput.md)
|
||||
:::
|
||||
|
||||
@ -27,5 +27,9 @@
|
||||
},
|
||||
"devDependencies": {
|
||||
"prettier": "^3.2.0"
|
||||
},
|
||||
"resolutions": {
|
||||
"markdown-it": "^14.1.1",
|
||||
"esbuild": "^0.25.0"
|
||||
}
|
||||
}
|
||||
|
||||
File diff suppressed because one or more lines are too long
932
docs/yarn.lock
932
docs/yarn.lock
File diff suppressed because it is too large
Load Diff
@ -645,7 +645,7 @@ int uORBTest::UnitTest::test_wrap_around()
|
||||
}
|
||||
#define CHECK_COPY(i_got, i_correct) \
|
||||
orb_copy(ORB_ID(orb_test_medium_wrap_around), sfd, &u); \
|
||||
if (i_got != i_correct) { \
|
||||
if ((i_got) != (i_correct)) { \
|
||||
return test_fail("got wrong element from the queue (got %i, should be %i)", i_got, i_correct); \
|
||||
}
|
||||
|
||||
@ -875,7 +875,7 @@ int uORBTest::UnitTest::test_queue()
|
||||
}
|
||||
#define CHECK_COPY(i_got, i_correct) \
|
||||
orb_copy(ORB_ID(orb_test_medium_queue), sfd, &u); \
|
||||
if (i_got != i_correct) { \
|
||||
if ((i_got) != (i_correct)) { \
|
||||
return test_fail("got wrong element from the queue (got %i, should be %i)", i_got, i_correct); \
|
||||
}
|
||||
|
||||
|
||||
@ -88,7 +88,7 @@ typedef enum : int32_t {
|
||||
TRIGGER_MODE_DISTANCE_ON_CMD
|
||||
} trigger_mode_t;
|
||||
|
||||
#define commandParamToInt(n) static_cast<int>(n >= 0 ? n + 0.5f : n - 0.5f)
|
||||
#define commandParamToInt(n) static_cast<int>((n) >= 0 ? (n) + 0.5f : (n) - 0.5f)
|
||||
|
||||
class CameraTrigger final : public px4::ScheduledWorkItem
|
||||
{
|
||||
|
||||
@ -51,8 +51,8 @@
|
||||
# define debug(fmt, args...) do { } while(0)
|
||||
#endif
|
||||
|
||||
#define CODER_CHECK(_c) do { if (_c->dead) { PX4_ERR("coder dead"); return -1; }} while(0)
|
||||
#define CODER_KILL(_c, _reason) do { PX4_ERR("killed: %s", _reason); _c->dead = true; return -1; } while(0)
|
||||
#define CODER_CHECK(_c) do { if ((_c)->dead) { PX4_ERR("coder dead"); return -1; }} while(0)
|
||||
#define CODER_KILL(_c, _reason) do { PX4_ERR("killed: %s", _reason); (_c)->dead = true; return -1; } while(0)
|
||||
|
||||
static int
|
||||
read_x(bson_decoder_t decoder, void *p, size_t s)
|
||||
|
||||
@ -46,7 +46,7 @@
|
||||
#include <errno.h>
|
||||
|
||||
#define BEAT_TIME_CONVERSION_MS (60 * 1000 * 4)
|
||||
#define BEAT_TIME_CONVERSION_US BEAT_TIME_CONVERSION_MS * 1000
|
||||
#define BEAT_TIME_CONVERSION_US (BEAT_TIME_CONVERSION_MS * 1000)
|
||||
#define BEAT_TIME_CONVERSION BEAT_TIME_CONVERSION_US
|
||||
|
||||
// semitone offsets from C for the characters 'A'-'G'
|
||||
|
||||
@ -1,6 +1,5 @@
|
||||
matplotlib==3.5.1
|
||||
numpy==1.22.2
|
||||
numpy==1.21.5
|
||||
numpy_quaternion==2022.4.3
|
||||
pyulog==0.9.0
|
||||
scipy==1.8.0
|
||||
|
||||
@ -92,8 +92,10 @@ parameters:
|
||||
by this parameter. The range sensor and vision options should only be used
|
||||
when for operation over a flat surface as the local NED origin will move
|
||||
up and down with ground level.
|
||||
If GPS is set as reference but altitude fusion is disabled in EKF2_GPS_CTRL,
|
||||
the GPS altitude is still used to initiaize the bias of the other height sensors.
|
||||
|
||||
If GPS is set as reference and EKF2_GPS_CTRL is not 0, the GPS altitude is
|
||||
still used to initiaize the bias of the other height sensors, regardless of
|
||||
the altitude fusion bit in EKF2_GPS_CTRL.
|
||||
type: enum
|
||||
values:
|
||||
0: Barometric pressure
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user