Skip to content

Commit 530979a

Browse files
committed
extras: re-generate all cog scripts
1 parent 42a8aff commit 530979a

File tree

4 files changed

+13
-13
lines changed

4 files changed

+13
-13
lines changed

mavros/src/plugins/sys_status.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -238,7 +238,7 @@ class SystemStatusDiag : public diagnostic_updater::DiagnosticTask
238238
check_flag("z/altitude control", STS::Z_ALTITUDE_CONTROL);
239239
check_flag("x/y position control", STS::XY_POSITION_CONTROL);
240240
check_flag("motor outputs / control", STS::MOTOR_OUTPUTS);
241-
check_flag("rc receiver", STS::RC_RECEIVER);
241+
check_flag("RC receiver", STS::RC_RECEIVER);
242242
check_flag("2nd 3D gyro", STS::SENSOR_3D_GYRO2);
243243
check_flag("2nd 3D accelerometer", STS::SENSOR_3D_ACCEL2);
244244
check_flag("2nd 3D magnetometer", STS::SENSOR_3D_MAG2);
@@ -253,7 +253,7 @@ class SystemStatusDiag : public diagnostic_updater::DiagnosticTask
253253
check_flag("pre-arm check status. Always healthy when armed", STS::PREARM_CHECK);
254254
check_flag("Avoidance/collision prevention", STS::OBSTACLE_AVOIDANCE);
255255
check_flag("propulsion (actuator, esc, motor or propellor)", STS::PROPULSION);
256-
// [[[end]]] (checksum: 435a149e38737aac78b4be94b670a6dd)
256+
// [[[end]]] (checksum: 7fbf2799c5df4ad3ba0086e055b61b68)
257257

258258
stat.addf("CPU Load (%)", "%.1f", last_st.load / 10.0);
259259
stat.addf("Drop rate (%)", "%.1f", last_st.drop_rate_comm / 10.0);

mavros_extras/CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -130,7 +130,7 @@ add_library(mavros_extras_plugins SHARED
130130
src/plugins/vision_pose_estimate.cpp
131131
src/plugins/vision_speed_estimate.cpp
132132
src/plugins/wheel_odometry.cpp
133-
# [[[end]]] (checksum: 1f8cd51fa90b89b27ee35d276b5f8c83)
133+
# [[[end]]] (checksum: 4564d922cfa3d36bf2089dade2323259)
134134
)
135135
ament_target_dependencies(mavros_extras_plugins
136136
angles

mavros_extras/mavros_plugins.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -246,4 +246,4 @@ This plugin allows computing and publishing wheel odometry coming from FCU wheel
246246
Can use either wheel's RPM or WHEEL_DISTANCE messages (the latter gives better accuracy).</description>
247247
</class>
248248
</library>
249-
<!-- [[[end]]] (checksum: b45714611896c0f7cf634dc7aaf2cbd6) -->
249+
<!-- [[[end]]] (checksum: 03a498e746e958da9480aa6411d57a1f) -->

mavros_msgs/srv/SetMavFrame.srv

Lines changed: 9 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -7,19 +7,19 @@
77
# mavros_cog.idl_decl_enum('MAV_FRAME', 'FRAME_')
88
# ]]]
99
# MAV_FRAME
10-
uint8 FRAME_GLOBAL = 0 # Global (WGS84) coordinate frame + MSL altitude. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL).
10+
uint8 FRAME_GLOBAL = 0 # Global (WGS84) coordinate frame + altitude relative to mean sea level (MSL).
1111
uint8 FRAME_LOCAL_NED = 1 # NED local tangent frame (x: North, y: East, z: Down) with origin fixed relative to earth.
1212
uint8 FRAME_MISSION = 2 # NOT a coordinate frame, indicates a mission command.
13-
uint8 FRAME_GLOBAL_RELATIVE_ALT = 3 # Global (WGS84) coordinate frame + altitude relative to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location.
13+
uint8 FRAME_GLOBAL_RELATIVE_ALT = 3 # Global (WGS84) coordinate frame + altitude relative to the home position.
1414
uint8 FRAME_LOCAL_ENU = 4 # ENU local tangent frame (x: East, y: North, z: Up) with origin fixed relative to earth.
15-
uint8 FRAME_GLOBAL_INT = 5 # Global (WGS84) coordinate frame (scaled) + MSL altitude. First value / x: latitude in degrees*1E7, second value / y: longitude in degrees*1E7, third value / z: positive altitude over mean sea level (MSL).
16-
uint8 FRAME_GLOBAL_RELATIVE_ALT_INT = 6 # Global (WGS84) coordinate frame (scaled) + altitude relative to the home position. First value / x: latitude in degrees*1E7, second value / y: longitude in degrees*1E7, third value / z: positive altitude with 0 being at the altitude of the home location.
15+
uint8 FRAME_GLOBAL_INT = 5 # Global (WGS84) coordinate frame (scaled) + altitude relative to mean sea level (MSL).
16+
uint8 FRAME_GLOBAL_RELATIVE_ALT_INT = 6 # Global (WGS84) coordinate frame (scaled) + altitude relative to the home position.
1717
uint8 FRAME_LOCAL_OFFSET_NED = 7 # NED local tangent frame (x: North, y: East, z: Down) with origin that travels with the vehicle.
18-
uint8 FRAME_BODY_NED = 8 # Same as MAV_FRAME_LOCAL_NED when used to represent position values. Same as MAV_FRAME_BODY_FRD when used with velocity/accelaration values.
18+
uint8 FRAME_BODY_NED = 8 # Same as MAV_FRAME_LOCAL_NED when used to represent position values. Same as MAV_FRAME_BODY_FRD when used with velocity/acceleration values.
1919
uint8 FRAME_BODY_OFFSET_NED = 9 # This is the same as MAV_FRAME_BODY_FRD.
20-
uint8 FRAME_GLOBAL_TERRAIN_ALT = 10 # Global (WGS84) coordinate frame with AGL altitude (at the waypoint coordinate). First value / x: latitude in degrees, second value / y: longitude in degrees, third value / z: positive altitude in meters with 0 being at ground level in terrain model.
21-
uint8 FRAME_GLOBAL_TERRAIN_ALT_INT = 11 # Global (WGS84) coordinate frame (scaled) with AGL altitude (at the waypoint coordinate). First value / x: latitude in degrees*1E7, second value / y: longitude in degrees*1E7, third value / z: positive altitude in meters with 0 being at ground level in terrain model.
22-
uint8 FRAME_BODY_FRD = 12 # FRD local tangent frame (x: Forward, y: Right, z: Down) with origin that travels with vehicle. The forward axis is aligned to the front of the vehicle in the horizontal plane.
20+
uint8 FRAME_GLOBAL_TERRAIN_ALT = 10 # Global (WGS84) coordinate frame with AGL altitude (altitude at ground level).
21+
uint8 FRAME_GLOBAL_TERRAIN_ALT_INT = 11 # Global (WGS84) coordinate frame (scaled) with AGL altitude (altitude at ground level).
22+
uint8 FRAME_BODY_FRD = 12 # FRD local frame aligned to the vehicle's attitude (x: Forward, y: Right, z: Down) with an origin that travels with vehicle.
2323
uint8 FRAME_RESERVED_13 = 13 # MAV_FRAME_BODY_FLU - Body fixed frame of reference, Z-up (x: Forward, y: Left, z: Up).
2424
uint8 FRAME_RESERVED_14 = 14 # MAV_FRAME_MOCAP_NED - Odometry local coordinate frame of data given by a motion capture system, Z-down (x: North, y: East, z: Down).
2525
uint8 FRAME_RESERVED_15 = 15 # MAV_FRAME_MOCAP_ENU - Odometry local coordinate frame of data given by a motion capture system, Z-up (x: East, y: North, z: Up).
@@ -29,7 +29,7 @@ uint8 FRAME_RESERVED_18 = 18 # MAV_FRAME_ESTIM_NED - Odometry local
2929
uint8 FRAME_RESERVED_19 = 19 # MAV_FRAME_ESTIM_ENU - Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-up (x: East, y: North, z: Up).
3030
uint8 FRAME_LOCAL_FRD = 20 # FRD local tangent frame (x: Forward, y: Right, z: Down) with origin fixed relative to earth. The forward axis is aligned to the front of the vehicle in the horizontal plane.
3131
uint8 FRAME_LOCAL_FLU = 21 # FLU local tangent frame (x: Forward, y: Left, z: Up) with origin fixed relative to earth. The forward axis is aligned to the front of the vehicle in the horizontal plane.
32-
# [[[end]]] (checksum: c5ddb537c91e87c4efba8b24c9cde50e)
32+
# [[[end]]] (checksum: 90ebc90d8774905ddaf66bdbdd0723c4)
3333

3434
uint8 mav_frame
3535
---

0 commit comments

Comments
 (0)