Skip to content

Commit

Permalink
build: patches: Add move_mav_cmd_fixed_mag_cal_yaw_to_common
Browse files Browse the repository at this point in the history
Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
  • Loading branch information
patrickelectric committed Jan 5, 2024
1 parent e6cdb44 commit c1f6df2
Showing 1 changed file with 42 additions and 0 deletions.
42 changes: 42 additions & 0 deletions build/patches/move_mav_cmd_fixed_mag_cal_yaw_to_common.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
diff --git a/message_definitions/v1.0/ardupilotmega.xml b/message_definitions/v1.0/ardupilotmega.xml
index 35e57c0a..4af5f9c4 100644
--- a/message_definitions/v1.0/ardupilotmega.xml
+++ b/message_definitions/v1.0/ardupilotmega.xml
@@ -121,16 +121,6 @@
<param index="6">Empty.</param>
<param index="7">Empty.</param>
</entry>
- <entry value="42006" name="MAV_CMD_FIXED_MAG_CAL_YAW">
- <description>Magnetometer calibration based on provided known yaw. This allows for fast calibration using WMM field tables in the vehicle, given only the known yaw of the vehicle. If Latitude and longitude are both zero then use the current vehicle location.</description>
- <param index="1" label="Yaw" units="deg">Yaw of vehicle in earth frame.</param>
- <param index="2" label="CompassMask">CompassMask, 0 for all.</param>
- <param index="3" label="Latitude" units="deg">Latitude.</param>
- <param index="4" label="Longitude" units="deg">Longitude.</param>
- <param index="5">Empty.</param>
- <param index="6">Empty.</param>
- <param index="7">Empty.</param>
- </entry>
<entry value="42424" name="MAV_CMD_DO_START_MAG_CAL">
<description>Initiate a magnetometer calibration.</description>
<param index="1">uint8_t bitmask of magnetometers (0 means all).</param>
diff --git a/message_definitions/v1.0/common.xml b/message_definitions/v1.0/common.xml
index 1ccad646..13c205cb 100644
--- a/message_definitions/v1.0/common.xml
+++ b/message_definitions/v1.0/common.xml
@@ -2540,6 +2540,16 @@
<param index="6" label="Longitude" units="degE7">Longitude. Note, if used in MISSION_ITEM (deprecated) the units are degrees (unscaled)</param>
<param index="7" label="Altitude" units="m">Altitude (MSL)</param>
</entry>
+ <entry value="42006" name="MAV_CMD_FIXED_MAG_CAL_YAW">
+ <description>Magnetometer calibration based on provided known yaw. This allows for fast calibration using WMM field tables in the vehicle, given only the known yaw of the vehicle. If Latitude and longitude are both zero then use the current vehicle location.</description>
+ <param index="1" label="Yaw" units="deg">Yaw of vehicle in earth frame.</param>
+ <param index="2" label="CompassMask">CompassMask, 0 for all.</param>
+ <param index="3" label="Latitude" units="deg">Latitude.</param>
+ <param index="4" label="Longitude" units="deg">Longitude.</param>
+ <param index="5">Empty.</param>
+ <param index="6">Empty.</param>
+ <param index="7">Empty.</param>
+ </entry>
<entry value="30002" name="MAV_CMD_PAYLOAD_CONTROL_DEPLOY" hasLocation="false" isDestination="false">
<description>Control the payload deployment.</description>
<param index="1" label="Operation Mode" minValue="0" maxValue="101" increment="1">Operation mode. 0: Abort deployment, continue normal mission. 1: switch to payload deployment mode. 100: delete first payload deployment request. 101: delete all payload deployment requests.</param>

0 comments on commit c1f6df2

Please sign in to comment.