Browse Source

add timestamp field to uORB msgs; sync timestamp whenever possible

sbg
TSC21 7 years ago committed by Beat Küng
parent
commit
e932030d88
  1. 1
      msg/actuator_armed.msg
  2. 2
      msg/actuator_controls.msg
  3. 1
      msg/actuator_direct.msg
  4. 1
      msg/actuator_outputs.msg
  5. 1
      msg/adc_report.msg
  6. 1
      msg/airspeed.msg
  7. 1
      msg/att_pos_mocap.msg
  8. 1
      msg/battery_status.msg
  9. 1
      msg/camera_capture.msg
  10. 1
      msg/camera_trigger.msg
  11. 1
      msg/collision_report.msg
  12. 3
      msg/commander_state.msg
  13. 1
      msg/cpuload.msg
  14. 2
      msg/debug_key_value.msg
  15. 2
      msg/debug_value.msg
  16. 2
      msg/debug_vect.msg
  17. 1
      msg/differential_pressure.msg
  18. 1
      msg/distance_sensor.msg
  19. 1
      msg/ekf2_innovations.msg
  20. 6
      msg/ekf2_timestamps.msg
  21. 1
      msg/ekf_gps_position.msg
  22. 1
      msg/esc_report.msg
  23. 1
      msg/esc_status.msg
  24. 1
      msg/estimator_status.msg
  25. 1
      msg/follow_target.msg
  26. 1
      msg/fw_pos_ctrl_status.msg
  27. 1
      msg/geofence_result.msg
  28. 2
      msg/gps_dump.msg
  29. 1
      msg/gps_inject_data.msg
  30. 2
      msg/home_position.msg
  31. 2
      msg/input_rc.msg
  32. 3
      msg/iridiumsbd_status.msg
  33. 2
      msg/irlock_report.msg
  34. 1
      msg/landing_target_innovations.msg
  35. 2
      msg/landing_target_pose.msg
  36. 2
      msg/led_control.msg
  37. 3
      msg/log_message.msg
  38. 1
      msg/manual_control_setpoint.msg
  39. 1
      msg/mavlink_log.msg
  40. 3
      msg/mission.msg
  41. 1
      msg/mission_result.msg
  42. 1
      msg/mount_orientation.msg
  43. 1
      msg/multirotor_motor_limits.msg
  44. 1
      msg/obstacle_distance.msg
  45. 2
      msg/offboard_control_mode.msg
  46. 4
      msg/optical_flow.msg
  47. 2
      msg/parameter_update.msg
  48. 1
      msg/ping.msg
  49. 2
      msg/position_setpoint.msg
  50. 2
      msg/position_setpoint_triplet.msg
  51. 2
      msg/power_button_state.msg
  52. 4
      msg/pwm_input.msg
  53. 1
      msg/qshell_req.msg
  54. 1
      msg/qshell_retval.msg
  55. 1
      msg/rate_ctrl_status.msg
  56. 2
      msg/rc_channels.msg
  57. 1
      msg/rc_parameter_map.msg
  58. 1
      msg/safety.msg
  59. 1
      msg/satellite_info.msg
  60. 1
      msg/sensor_accel.msg
  61. 1
      msg/sensor_baro.msg
  62. 2
      msg/sensor_bias.msg
  63. 2
      msg/sensor_combined.msg
  64. 2
      msg/sensor_correction.msg
  65. 2
      msg/sensor_gyro.msg
  66. 1
      msg/sensor_mag.msg
  67. 1
      msg/sensor_preflight.msg
  68. 2
      msg/sensor_selection.msg
  69. 1
      msg/servorail_status.msg
  70. 2
      msg/subsystem_info.msg
  71. 1
      msg/system_power.msg
  72. 2
      msg/task_stack_info.msg
  73. 1
      msg/tecs_status.msg
  74. 2
      msg/telemetry_status.msg
  75. 2
      msg/templates/uorb/msg.cpp.template
  76. 2
      msg/templates/uorb/msg.h.template
  77. 2
      msg/templates/uorb_microcdr/msg.cpp.template
  78. 3
      msg/templates/urtps/msg.idl.template
  79. 1
      msg/test_motor.msg
  80. 3
      msg/timesync_status.msg
  81. 1
      msg/trajectory_waypoint.msg
  82. 1
      msg/transponder_report.msg
  83. 2
      msg/tune_control.msg
  84. 1
      msg/uavcan_parameter_request.msg
  85. 1
      msg/uavcan_parameter_value.msg
  86. 3
      msg/ulog_stream.msg
  87. 5
      msg/ulog_stream_ack.msg
  88. 1
      msg/vehicle_air_data.msg
  89. 2
      msg/vehicle_attitude.msg
  90. 1
      msg/vehicle_attitude_setpoint.msg
  91. 37
      msg/vehicle_command.msg
  92. 1
      msg/vehicle_command_ack.msg
  93. 2
      msg/vehicle_constraints.msg
  94. 6
      msg/vehicle_control_mode.msg
  95. 2
      msg/vehicle_global_position.msg
  96. 24
      msg/vehicle_gps_position.msg
  97. 1
      msg/vehicle_land_detected.msg
  98. 4
      msg/vehicle_local_position.msg
  99. 2
      msg/vehicle_local_position_setpoint.msg
  100. 1
      msg/vehicle_magnetometer.msg
  101. Some files were not shown because too many files have changed in this diff Show More

1
msg/actuator_armed.msg

@ -1,3 +1,4 @@ @@ -1,3 +1,4 @@
uint64 timestamp # time since system start (microseconds)
uint32 armed_time_ms # Arming timestamp
bool armed # Set to true if system is armed

2
msg/actuator_controls.msg

@ -1,3 +1,4 @@ @@ -1,3 +1,4 @@
uint64 timestamp # time since system start (microseconds)
uint8 NUM_ACTUATOR_CONTROLS = 8
uint8 NUM_ACTUATOR_CONTROL_GROUPS = 4
uint8 INDEX_ROLL = 0
@ -15,4 +16,3 @@ float32[8] control @@ -15,4 +16,3 @@ float32[8] control
# TOPICS actuator_controls actuator_controls_0 actuator_controls_1 actuator_controls_2 actuator_controls_3
# TOPICS actuator_controls_virtual_fw actuator_controls_virtual_mc

1
msg/actuator_direct.msg

@ -1,3 +1,4 @@ @@ -1,3 +1,4 @@
uint64 timestamp # time since system start (microseconds)
uint8 NUM_ACTUATORS_DIRECT = 16
uint32 nvalues # number of valid values
float32[16] values # actuator values, from -1 to 1

1
msg/actuator_outputs.msg

@ -1,3 +1,4 @@ @@ -1,3 +1,4 @@
uint64 timestamp # time since system start (microseconds)
uint8 NUM_ACTUATOR_OUTPUTS = 16
uint8 NUM_ACTUATOR_OUTPUT_GROUPS = 4 # for sanity checking
uint32 noutputs # valid outputs

1
msg/adc_report.msg

@ -1,2 +1,3 @@ @@ -1,2 +1,3 @@
uint64 timestamp # time since system start (microseconds)
int16[12] channel_id # ADC channel IDs, negative for non-existent
float32[12] channel_value # ADC channel value in volt, valid if channel ID is positive

1
msg/airspeed.msg

@ -1,3 +1,4 @@ @@ -1,3 +1,4 @@
uint64 timestamp # time since system start (microseconds)
float32 indicated_airspeed_m_s # indicated airspeed in m/s

1
msg/att_pos_mocap.msg

@ -1,3 +1,4 @@ @@ -1,3 +1,4 @@
uint64 timestamp # time since system start (microseconds)
uint32 id # ID of the estimator, commonly the component ID of the incoming message
uint64 timestamp_received # timestamp when the estimate was received

1
msg/battery_status.msg

@ -1,3 +1,4 @@ @@ -1,3 +1,4 @@
uint64 timestamp # time since system start (microseconds)
float32 voltage_v # Battery voltage in volts, 0 if unknown
float32 voltage_filtered_v # Battery voltage in volts, filtered, 0 if unknown
float32 current_a # Battery current in amperes, -1 if unknown

1
msg/camera_capture.msg

@ -1,3 +1,4 @@ @@ -1,3 +1,4 @@
uint64 timestamp # time since system start (microseconds)
uint64 timestamp_utc # Capture time in UTC / GPS time
uint32 seq # Image sequence number
float64 lat # Latitude in degrees (WGS84)

1
msg/camera_trigger.msg

@ -1,3 +1,4 @@ @@ -1,3 +1,4 @@
uint64 timestamp # time since system start (microseconds)
uint64 timestamp_utc # UTC timestamp
uint32 seq # Image sequence number

1
msg/collision_report.msg

@ -1,3 +1,4 @@ @@ -1,3 +1,4 @@
uint64 timestamp # time since system start (microseconds)
uint8 src
uint32 id
uint8 action

3
msg/commander_state.msg

@ -1,4 +1,6 @@ @@ -1,4 +1,6 @@
# Main state, i.e. what user wants. Controlled by RC or from ground station via telemetry link.
uint64 timestamp # time since system start (microseconds)
uint8 MAIN_STATE_MANUAL = 0
uint8 MAIN_STATE_ALTCTL = 1
uint8 MAIN_STATE_POSCTL = 2
@ -15,5 +17,4 @@ uint8 MAIN_STATE_AUTO_FOLLOW_TARGET = 12 @@ -15,5 +17,4 @@ uint8 MAIN_STATE_AUTO_FOLLOW_TARGET = 12
uint8 MAIN_STATE_AUTO_PRECLAND = 13
uint8 MAIN_STATE_MAX = 14
uint8 main_state # main state machine

1
msg/cpuload.msg

@ -1,2 +1,3 @@ @@ -1,2 +1,3 @@
uint64 timestamp # time since system start (microseconds)
float32 load # processor load from 0 to 1
float32 ram_usage # RAM usage from 0 to 1

2
msg/debug_key_value.msg

@ -1,3 +1,3 @@ @@ -1,3 +1,3 @@
uint32 timestamp_ms # in milliseconds since system start
uint64 timestamp # time since system start (microseconds)
char[10] key # max. 10 characters as key / name
float32 value # the value to send as debug output

2
msg/debug_value.msg

@ -1,3 +1,3 @@ @@ -1,3 +1,3 @@
uint32 timestamp_ms # in milliseconds since system start
uint64 timestamp # time since system start (microseconds)
int8 ind # index of debug variable
float32 value # the value to send as debug output

2
msg/debug_vect.msg

@ -1,4 +1,4 @@ @@ -1,4 +1,4 @@
uint64 timestamp_us # in microseconds since system start
uint64 timestamp # time since system start (microseconds)
char[10] name # max. 10 characters as key / name
float32 x # x value
float32 y # y value

1
msg/differential_pressure.msg

@ -1,3 +1,4 @@ @@ -1,3 +1,4 @@
uint64 timestamp # time since system start (microseconds)
uint64 error_count # Number of errors detected by driver
float32 differential_pressure_raw_pa # Raw differential pressure reading (may be negative)
float32 differential_pressure_filtered_pa # Low pass filtered differential pressure reading

1
msg/distance_sensor.msg

@ -1,5 +1,6 @@ @@ -1,5 +1,6 @@
# DISTANCE_SENSOR message data
uint64 timestamp # time since system start (microseconds)
float32 min_distance # Minimum distance the sensor can measure (in m)
float32 max_distance # Maximum distance the sensor can measure (in m)

1
msg/ekf2_innovations.msg

@ -1,3 +1,4 @@ @@ -1,3 +1,4 @@
uint64 timestamp # time since system start (microseconds)
float32[6] vel_pos_innov # velocity and position innovations
float32[3] mag_innov # earth magnetic field innovations
float32 heading_innov # heading innovation

6
msg/ekf2_timestamps.msg

@ -1,9 +1,10 @@ @@ -1,9 +1,10 @@
# this message contains the (relative) timestamps of the sensor inputs used by
# ekf2. It can be used for reproducible replay.
# the timestamp field (auto-generated) is the ekf2 reference time and matches
# the timestamp of the sensor_combined topic.
# the timestamp field is the ekf2 reference time and matches the timestamp of
# the sensor_combined topic.
uint64 timestamp # time since system start (microseconds)
int16 RELATIVE_TIMESTAMP_INVALID = 32767 # (0x7fff) If one of the relative timestamps
# is set to this value, it means the associated sensor values did not update
@ -22,4 +23,3 @@ int16 vision_attitude_timestamp_rel @@ -22,4 +23,3 @@ int16 vision_attitude_timestamp_rel
int16 vision_position_timestamp_rel
# Note: this is a high-rate logged topic, so it needs to be as small as possible

1
msg/ekf_gps_position.msg

@ -1,4 +1,5 @@ @@ -1,4 +1,5 @@
# EKF blended position in WGS84 coordinates.
uint64 timestamp # time since system start (microseconds)
int32 lat # Latitude in 1E-7 degrees
int32 lon # Longitude in 1E-7 degrees
int32 alt # Altitude in 1E-3 meters above MSL, (millimetres)

1
msg/esc_report.msg

@ -1,3 +1,4 @@ @@ -1,3 +1,4 @@
uint64 timestamp # time since system start (microseconds)
uint8 esc_vendor # Vendor of current ESC
uint32 esc_errorcount # Number of reported errors by ESC - if supported
int32 esc_rpm # Motor RPM, negative for reverse rotation [RPM] - if supported

1
msg/esc_status.msg

@ -1,3 +1,4 @@ @@ -1,3 +1,4 @@
uint64 timestamp # time since system start (microseconds)
uint8 CONNECTED_ESC_MAX = 8 # The number of ESCs supported. Current (Q2/2013) we support 8 ESCs
uint8 ESC_VENDOR_GENERIC = 0 # generic ESC

1
msg/estimator_status.msg

@ -1,3 +1,4 @@ @@ -1,3 +1,4 @@
uint64 timestamp # time since system start (microseconds)
float32[24] states # Internal filter states
uint8 n_states # Number of states effectively used

1
msg/follow_target.msg

@ -1,3 +1,4 @@ @@ -1,3 +1,4 @@
uint64 timestamp # time since system start (microseconds)
float64 lat # target position (deg * 1e7)
float64 lon # target position (deg * 1e7)
float32 alt # target position

1
msg/fw_pos_ctrl_status.msg

@ -1,3 +1,4 @@ @@ -1,3 +1,4 @@
uint64 timestamp # time since system start (microseconds)
float32 nav_roll
float32 nav_pitch
float32 nav_bearing

1
msg/geofence_result.msg

@ -1,3 +1,4 @@ @@ -1,3 +1,4 @@
uint64 timestamp # time since system start (microseconds)
uint8 GF_ACTION_NONE = 0 # no action on geofence violation
uint8 GF_ACTION_WARN = 1 # critical mavlink message
uint8 GF_ACTION_LOITER = 2 # switch to AUTO|LOITER

2
msg/gps_dump.msg

@ -1,6 +1,8 @@ @@ -1,6 +1,8 @@
# This message is used to dump the raw gps communication to the log.
# Set the parameter GPS_DUMP_COMM to 1 to use this.
uint64 timestamp # time since system start (microseconds)
uint8 len # length of data, MSB bit set = message to the gps device,
# clear = message from the device
uint8[79] data # data to write to the log

1
msg/gps_inject_data.msg

@ -1,3 +1,4 @@ @@ -1,3 +1,4 @@
uint64 timestamp # time since system start (microseconds)
uint8 len # length of data
uint8 flags # LSB: 1=fragmented
uint8[182] data # data to write to GPS device (RTCM message)

2
msg/home_position.msg

@ -1,5 +1,7 @@ @@ -1,5 +1,7 @@
# GPS home position in WGS84 coordinates.
uint64 timestamp # time since system start (microseconds)
float64 lat # Latitude in degrees
float64 lon # Longitude in degrees
float32 alt # Altitude in meters (AMSL)

2
msg/input_rc.msg

@ -1,3 +1,5 @@ @@ -1,3 +1,5 @@
uint64 timestamp # time since system start (microseconds)
uint8 RC_INPUT_SOURCE_UNKNOWN = 0
uint8 RC_INPUT_SOURCE_PX4FMU_PPM = 1
uint8 RC_INPUT_SOURCE_PX4IO_PPM = 2

3
msg/iridiumsbd_status.msg

@ -1,3 +1,4 @@ @@ -1,3 +1,4 @@
uint64 timestamp # time since system start (microseconds)
uint64 last_heartbeat # timestamp of the last successful sbd session
uint16 tx_buf_write_index # current size of the tx buffer
uint16 rx_buf_read_index # the rx buffer is parsed up to that index
@ -11,4 +12,4 @@ bool ring_pending # indicates if a ring call is pending @@ -11,4 +12,4 @@ bool ring_pending # indicates if a ring call is pending
bool tx_buf_write_pending # indicates if a tx buffer write is pending
bool tx_session_pending # indicates if a tx session is pending
bool rx_read_pending # indicates if a rx read is pending
bool rx_session_pending # indicates if a rx session is pending
bool rx_session_pending # indicates if a rx session is pending

2
msg/irlock_report.msg

@ -1,5 +1,7 @@ @@ -1,5 +1,7 @@
# IRLOCK_REPORT message data
uint64 timestamp # time since system start (microseconds)
uint16 signature
# When looking along the optical axis of the camera, x points right, y points down, and z points along the optical axis.

1
msg/landing_target_innovations.msg

@ -1,3 +1,4 @@ @@ -1,3 +1,4 @@
uint64 timestamp # time since system start (microseconds)
# Innovation of landing target position estimator
float32 innov_x
float32 innov_y

2
msg/landing_target_pose.msg

@ -1,5 +1,7 @@ @@ -1,5 +1,7 @@
# Relative position of precision land target in navigation (body fixed, north aligned, NED) and inertial (world fixed, north aligned, NED) frames
uint64 timestamp # time since system start (microseconds)
bool is_static # Flag indicating whether the landing target is static or moving with respect to the ground
bool rel_pos_valid # Flag showing whether relative position is valid

2
msg/led_control.msg

@ -1,6 +1,8 @@ @@ -1,6 +1,8 @@
# LED control: control a single or multiple LED's.
# These are the externally visible LED's, not the board LED's
uint64 timestamp # time since system start (microseconds)
# colors
uint8 COLOR_OFF = 0 # this is only used in the drivers
uint8 COLOR_RED = 1

3
msg/log_message.msg

@ -1,5 +1,6 @@ @@ -1,5 +1,6 @@
# A logging message, output with PX4_{WARN,ERR,INFO}
uint64 timestamp # time since system start (microseconds)
uint8 severity # log level (same as in the linux kernel, starting with 0)
uint8[127] text

1
msg/manual_control_setpoint.msg

@ -1,3 +1,4 @@ @@ -1,3 +1,4 @@
uint64 timestamp # time since system start (microseconds)
uint8 SWITCH_POS_NONE = 0 # switch is not mapped
uint8 SWITCH_POS_ON = 1 # switch activated (value = 1)

1
msg/mavlink_log.msg

@ -1,3 +1,4 @@ @@ -1,3 +1,4 @@
uint64 timestamp # time since system start (microseconds)
uint8[50] text
uint8 severity # log level (same as in the linux kernel, starting with 0)

3
msg/mission.msg

@ -1,4 +1,5 @@ @@ -1,4 +1,5 @@
uint64 timestamp # time since system start (microseconds)
uint8 dataman_id # default 0, there are two offboard storage places in the dataman: 0 or 1
uint16 count # count of the missions stored in the dataman
int32 current_seq # default -1, start at the one changed latest
int32 current_seq # default -1, start at the one changed latest

1
msg/mission_result.msg

@ -1,3 +1,4 @@ @@ -1,3 +1,4 @@
uint64 timestamp # time since system start (microseconds)
uint8 MISSION_EXECUTION_MODE_NORMAL = 0 # Execute the mission according to the planned items
uint8 MISSION_EXECUTION_MODE_REVERSE = 1 # Execute the mission in reverse order, ignoring commands and converting all waypoints to normal ones
uint8 MISSION_EXECUTION_MODE_FAST_FORWARD = 2 # Execute the mission as fast as possible, for example converting loiter waypoints to normal ones

1
msg/mount_orientation.msg

@ -1 +1,2 @@ @@ -1 +1,2 @@
uint64 timestamp # time since system start (microseconds)
float32[3] attitude_euler_angle # Attitude/direction of the mount as euler angles in rad

1
msg/multirotor_motor_limits.msg

@ -1,3 +1,4 @@ @@ -1,3 +1,4 @@
uint64 timestamp # time since system start (microseconds)
uint16 saturation_status # Integer bit mask indicating which axes in the control mixer are saturated
# 0 - True if the saturation status is valid

1
msg/obstacle_distance.msg

@ -1,4 +1,5 @@ @@ -1,4 +1,5 @@
# Obstacle distances in front of the sensor.
uint64 timestamp # time since system start (microseconds)
uint8 sensor_type # Type from MAV_DISTANCE_SENSOR enum.
uint8 MAV_DISTANCE_SENSOR_LASER = 0

2
msg/offboard_control_mode.msg

@ -1,5 +1,7 @@ @@ -1,5 +1,7 @@
# Off-board control mode
uint64 timestamp # time since system start (microseconds)
bool ignore_thrust
bool ignore_attitude
bool ignore_bodyrate

4
msg/optical_flow.msg

@ -1,6 +1,8 @@ @@ -1,6 +1,8 @@
# Optical flow in XYZ body frame in SI units.
# @see http://en.wikipedia.org/wiki/International_System_of_Units
uint64 timestamp # time since system start (microseconds)
uint8 sensor_id # id of the sensor emitting the flow value
float32 pixel_flow_x_integral # accumulated optical flow in radians where a positive value is produced by a RH rotation about the X body axis
float32 pixel_flow_y_integral # accumulated optical flow in radians where a positive value is produced by a RH rotation about the Y body axis
@ -16,4 +18,4 @@ uint8 quality # Average of quality of accumulated frames, 0: bad quality, 255: m @@ -16,4 +18,4 @@ uint8 quality # Average of quality of accumulated frames, 0: bad quality, 255: m
float32 max_flow_rate # Magnitude of maximum angular which the optical flow sensor can measure reliably
float32 min_ground_distance # Minimum distance from ground at which the optical flow sensor operates reliably
float32 max_ground_distance # Maximum distance from ground at which the optical flow sensor operates reliably
float32 max_ground_distance # Maximum distance from ground at which the optical flow sensor operates reliably

2
msg/parameter_update.msg

@ -1,3 +1,5 @@ @@ -1,3 +1,5 @@
# This message is used to notify the system about one or more parameter changes
uint64 timestamp # time since system start (microseconds)
uint32 instance # Instance count - constantly incrementing

1
msg/ping.msg

@ -1,3 +1,4 @@ @@ -1,3 +1,4 @@
uint64 timestamp # time since system start (microseconds)
uint64 ping_time # Timestamp of the ping packet
uint32 ping_sequence # Sequence number of the ping packet
uint32 dropped_packets # Number of dropped ping packets

2
msg/position_setpoint.msg

@ -1,5 +1,7 @@ @@ -1,5 +1,7 @@
# this file is only used in the position_setpoint triple as a dependency
uint64 timestamp # time since system start (microseconds)
uint8 SETPOINT_TYPE_POSITION=0 # position setpoint
uint8 SETPOINT_TYPE_VELOCITY=1 # velocity setpoint
uint8 SETPOINT_TYPE_LOITER=2 # loiter setpoint

2
msg/position_setpoint_triplet.msg

@ -1,6 +1,8 @@ @@ -1,6 +1,8 @@
# 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)
px4/position_setpoint previous
px4/position_setpoint current
px4/position_setpoint next

2
msg/power_button_state.msg

@ -1,5 +1,7 @@ @@ -1,5 +1,7 @@
# power button state notification message
uint64 timestamp # time since system start (microseconds)
uint8 PWR_BUTTON_STATE_IDEL = 0 # Button went up without meeting shutdown button down time (delete event)
uint8 PWR_BUTTON_STATE_DOWN = 1 # Button went Down
uint8 PWR_BUTTON_STATE_UP = 2 # Button went Up

4
msg/pwm_input.msg

@ -1,4 +1,4 @@ @@ -1,4 +1,4 @@
uint64 timestamp # time since system start (microseconds)
uint64 error_count
uint32 pulse_width # Pulse width, timer counts
uint32 pulse_width # Pulse width, timer counts
uint32 period # Period, timer counts

1
msg/qshell_req.msg

@ -1,3 +1,4 @@ @@ -1,3 +1,4 @@
uint64 timestamp # time since system start (microseconds)
uint8[100] cmd
uint32 MAX_STRLEN = 100
uint32 strlen

1
msg/qshell_retval.msg

@ -1,2 +1,3 @@ @@ -1,2 +1,3 @@
uint64 timestamp # time since system start (microseconds)
int32 return_value
uint32 sequence

1
msg/rate_ctrl_status.msg

@ -1,3 +1,4 @@ @@ -1,3 +1,4 @@
uint64 timestamp # time since system start (microseconds)
# rates used by the controller
float32 rollspeed # Bias corrected angular velocity about X body axis in rad/s

2
msg/rc_channels.msg

@ -1,3 +1,5 @@ @@ -1,3 +1,5 @@
uint64 timestamp # time since system start (microseconds)
uint8 RC_CHANNELS_FUNCTION_THROTTLE=0
uint8 RC_CHANNELS_FUNCTION_ROLL=1
uint8 RC_CHANNELS_FUNCTION_PITCH=2

1
msg/rc_parameter_map.msg

@ -1,3 +1,4 @@ @@ -1,3 +1,4 @@
uint64 timestamp # time since system start (microseconds)
uint8 RC_PARAM_MAP_NCHAN = 3 # This limit is also hardcoded in the enum RC_CHANNELS_FUNCTION in rc_channels.h
uint8 PARAM_ID_LEN = 16 # corresponds to MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN

1
msg/safety.msg

@ -1,3 +1,4 @@ @@ -1,3 +1,4 @@
uint64 timestamp # time since system start (microseconds)
bool safety_switch_available # Set to true if a safety switch is connected
bool safety_off # Set to true if safety is off
bool override_available # Set to true if external override system is connected

1
msg/satellite_info.msg

@ -1,3 +1,4 @@ @@ -1,3 +1,4 @@
uint64 timestamp # time since system start (microseconds)
uint8 SAT_INFO_MAX_SATELLITES = 20
uint8 count # Number of satellites in satellite info

1
msg/sensor_accel.msg

@ -1,3 +1,4 @@ @@ -1,3 +1,4 @@
uint64 timestamp # time since system start (microseconds)
uint32 device_id # unique device ID for the sensor that does not change between power cycles
uint64 error_count

1
msg/sensor_baro.msg

@ -1,3 +1,4 @@ @@ -1,3 +1,4 @@
uint64 timestamp # time since system start (microseconds)
uint32 device_id # Sensor ID that must be unique for each baro sensor and must not change
uint64 error_count

2
msg/sensor_bias.msg

@ -3,6 +3,8 @@ @@ -3,6 +3,8 @@
# scale errors, in-run bias and thermal drift (if thermal compensation is enabled and available).
#
uint64 timestamp # time since system start (microseconds)
float32 accel_x # Bias corrected acceleration in body X axis (in m/s^2)
float32 accel_y # Bias corrected acceleration in body Y axis (in m/s^2)
float32 accel_z # Bias corrected acceleration in body Z axis (in m/s^2)

2
msg/sensor_combined.msg

@ -5,6 +5,8 @@ @@ -5,6 +5,8 @@
# change with board revisions and sensor updates.
#
uint64 timestamp # time since system start (microseconds)
int32 RELATIVE_TIMESTAMP_INVALID = 2147483647 # (0x7fffffff) If one of the relative timestamps is set to this value, it means the associated sensor values are invalid
# gyro timstamp is equal to the timestamp of the message

2
msg/sensor_correction.msg

@ -2,6 +2,8 @@ @@ -2,6 +2,8 @@
# Sensor corrections in SI-unit form for the voted sensor
#
uint64 timestamp # time since system start (microseconds)
# Corrections for gyro angular rate outputs where corrected_rate = raw_rate * gyro_scale + gyro_offset
# Note the corrections are in the sensor frame and must be applied before the sensor data is rotated into body frame
# corrections for uORB instance 0

2
msg/sensor_gyro.msg

@ -1,5 +1,7 @@ @@ -1,5 +1,7 @@
uint32 device_id # unique device ID for the sensor that does not change between power cycles
uint64 timestamp # time since system start (microseconds)
uint64 error_count
float32 x # angular velocity in the NED X board axis in rad/s

1
msg/sensor_mag.msg

@ -1,3 +1,4 @@ @@ -1,3 +1,4 @@
uint64 timestamp # time since system start (microseconds)
uint32 device_id # unique device ID for the sensor that does not change between power cycles
uint64 error_count

1
msg/sensor_preflight.msg

@ -2,6 +2,7 @@ @@ -2,6 +2,7 @@
# Pre-flight sensor check metrics. These will be zero if the vehicle only has one sensor.
# The topic will not be updated when the vehicle is armed
#
uint64 timestamp # time since system start (microseconds)
float32 accel_inconsistency_m_s_s # magnitude of maximum acceleration difference between IMU instances in (m/s/s).
float32 gyro_inconsistency_rad_s # magnitude of maximum angular rate difference between IMU instances in (rad/s).
float32 mag_inconsistency_ga # magnitude of maximum difference between Mag instances in (Gauss).

2
msg/sensor_selection.msg

@ -2,7 +2,7 @@ @@ -2,7 +2,7 @@
# Sensor ID's for the voted sensors output on the sensor_combined topic.
# Will be updated on startup of the sensor module and when sensor selection changes
#
uint64 timestamp # time since system start (microseconds)
uint32 accel_device_id # unique device ID for the selected accelerometers
uint32 baro_device_id # unique device ID for the selected barometer
uint32 gyro_device_id # unique device ID for the selected rate gyros

1
msg/servorail_status.msg

@ -1,2 +1,3 @@ @@ -1,2 +1,3 @@
uint64 timestamp # time since system start (microseconds)
float32 voltage_v # Servo rail voltage in volts
float32 rssi_v # RSSI pin voltage in volts

2
msg/subsystem_info.msg

@ -1,3 +1,5 @@ @@ -1,3 +1,5 @@
uint64 timestamp # time since system start (microseconds)
uint64 SUBSYSTEM_TYPE_GYRO = 1
uint64 SUBSYSTEM_TYPE_ACC = 2
uint64 SUBSYSTEM_TYPE_MAG = 4

1
msg/system_power.msg

@ -1,3 +1,4 @@ @@ -1,3 +1,4 @@
uint64 timestamp # time since system start (microseconds)
float32 voltage5v_v # peripheral 5V rail voltage
float32 voltage3v3_v # Sensor 3V3 rail voltage
uint8 v3v3_valid # Sensor 3V3 rail voltage was read.

2
msg/task_stack_info.msg

@ -1,5 +1,7 @@ @@ -1,5 +1,7 @@
# stack information for a single running process
uint64 timestamp # time since system start (microseconds)
uint8 MAX_REPORT_TASK_NAME_LEN = 16
uint16 stack_free

1
msg/tecs_status.msg

@ -1,3 +1,4 @@ @@ -1,3 +1,4 @@
uint64 timestamp # time since system start (microseconds)
uint8 TECS_MODE_NORMAL = 0
uint8 TECS_MODE_UNDERSPEED = 1
uint8 TECS_MODE_TAKEOFF = 2

2
msg/telemetry_status.msg

@ -1,3 +1,5 @@ @@ -1,3 +1,5 @@
uint64 timestamp # time since system start (microseconds)
uint8 TELEMETRY_STATUS_RADIO_TYPE_GENERIC = 0
uint8 TELEMETRY_STATUS_RADIO_TYPE_3DR_RADIO = 1
uint8 TELEMETRY_STATUS_RADIO_TYPE_UBIQUITY_BULLET = 2

2
msg/templates/uorb/msg.cpp.template

@ -61,7 +61,7 @@ topic_name = spec.short_name @@ -61,7 +61,7 @@ topic_name = spec.short_name
sorted_fields = sorted(spec.parsed_fields(), key=sizeof_field_type, reverse=True)
struct_size, padding_end_size = add_padding_bytes(sorted_fields, search_path)
topic_fields = ["uint64_t timestamp"]+["%s %s" % (convert_type(field.type), field.name) for field in sorted_fields]
topic_fields = ["%s %s" % (convert_type(field.type), field.name) for field in sorted_fields]
}@
#include <cinttypes>

2
msg/templates/uorb/msg.h.template

@ -110,8 +110,6 @@ struct __EXPORT @(uorb_struct) { @@ -110,8 +110,6 @@ struct __EXPORT @(uorb_struct) {
#else
struct @(uorb_struct) {
#endif
@# timestamp at the beginning of each topic is required for logger
uint64_t timestamp; // required for logger
@print_parsed_fields()
#ifdef __cplusplus

2
msg/templates/uorb_microcdr/msg.cpp.template

@ -147,7 +147,6 @@ void serialize_@(topic_name)(MicroBuffer *microCDRWriter, const struct @(uorb_st @@ -147,7 +147,6 @@ void serialize_@(topic_name)(MicroBuffer *microCDRWriter, const struct @(uorb_st
reset_micro_buffer(microCDRWriter);
serialize_uint64_t(microCDRWriter, input->timestamp);
@add_code_to_serialize()
(*length) = micro_buffer_length(microCDRWriter);
}
@ -159,6 +158,5 @@ void deserialize_@(topic_name)(MicroBuffer *microCDRReader, struct @(uorb_struct @@ -159,6 +158,5 @@ void deserialize_@(topic_name)(MicroBuffer *microCDRReader, struct @(uorb_struct
reset_micro_buffer(microCDRReader);
deserialize_uint64_t(microCDRReader, &output->timestamp);
@add_code_to_deserialize()
}

3
msg/templates/urtps/msg.idl.template

@ -65,11 +65,10 @@ def add_msg_fields(): @@ -65,11 +65,10 @@ def add_msg_fields():
for field in sorted_fields:
add_msg_field(field)
}@
@
struct @(spec.short_name)_
{
unsigned long long timestamp;
@add_msg_fields()
}; // struct @(spec.short_name)_

1
msg/test_motor.msg

@ -1,3 +1,4 @@ @@ -1,3 +1,4 @@
uint64 timestamp # time since system start (microseconds)
uint8 NUM_MOTOR_OUTPUTS = 8
uint32 motor_number # number of motor to spin

3
msg/timesync_status.msg

@ -1,4 +1,5 @@ @@ -1,4 +1,5 @@
uint64 timestamp # time since system start (microseconds)
uint64 remote_timestamp # remote system timestamp (microseconds)
int64 observed_offset # raw time offset directly observed from this timesync packet (microseconds)
int64 estimated_offset # smoothed time offset between companion system and PX4 (microseconds)
uint32 round_trip_time # round trip time of this timesync packet (microseconds)
uint32 round_trip_time # round trip time of this timesync packet (microseconds)

1
msg/trajectory_waypoint.msg

@ -1,6 +1,7 @@ @@ -1,6 +1,7 @@
# Waypoint Trajectory description. See also Mavlink TRAJECTORY msg
# The topic trajectory_waypoint describe each waypoint defined in vehicle_trajectory_waypoint
uint64 timestamp # time since system start (microseconds)
float32[3] position
float32[3] velocity

1
msg/transponder_report.msg

@ -1,3 +1,4 @@ @@ -1,3 +1,4 @@
uint64 timestamp # time since system start (microseconds)
uint32 icao_address # ICAO address
float64 lat # Latitude, expressed as degrees
float64 lon # Longitude, expressed as degrees

2
msg/tune_control.msg

@ -1,6 +1,8 @@ @@ -1,6 +1,8 @@
# This message is used to control the tunes, when the tune_id is set to CUSTOM
# then the frequency, duration are used otherwise those values are ignored.
uint64 timestamp # time since system start (microseconds)
uint8 tune_id # tune_id corresponding to TuneID::* from the tune_defaults.h in the tunes library
uint8 tune_override # if set to 1 the tune which is playing will be stopped and the new started
uint16 frequency # in Hz

1
msg/uavcan_parameter_request.msg

@ -1,4 +1,5 @@ @@ -1,4 +1,5 @@
# UAVCAN-MAVLink parameter bridge request type
uint64 timestamp # time since system start (microseconds)
uint8 message_type # MAVLink message type: PARAM_REQUEST_READ, PARAM_REQUEST_LIST, PARAM_SET
uint8 node_id # UAVCAN node ID mapped from MAVLink component ID
char[17] param_id # MAVLink/UAVCAN parameter name

1
msg/uavcan_parameter_value.msg

@ -1,4 +1,5 @@ @@ -1,4 +1,5 @@
# UAVCAN-MAVLink parameter bridge response type
uint64 timestamp # time since system start (microseconds)
uint8 node_id # UAVCAN node ID mapped from MAVLink component ID
char[17] param_id # MAVLink/UAVCAN parameter name
int16 param_index # parameter index, if known

3
msg/ulog_stream.msg

@ -1,6 +1,8 @@ @@ -1,6 +1,8 @@
# Message to stream ULog data from the logger. Corresponds to the LOGGING_DATA
# mavlink message
uint64 timestamp # time since system start (microseconds)
# flags bitmasks
uint8 FLAGS_NEED_ACK = 1 # if set, this message requires to be acked.
# Acked messages are published synchronous: a
@ -13,4 +15,3 @@ uint8 first_message_offset # offset into data where first message starts. This @@ -13,4 +15,3 @@ uint8 first_message_offset # offset into data where first message starts. This
uint16 sequence # allows determine drops
uint8 flags # see FLAGS_*
uint8[249] data # ulog data

5
msg/ulog_stream_ack.msg

@ -1,7 +1,8 @@ @@ -1,7 +1,8 @@
# Ack a previously sent ulog_stream message that had
# the NEED_ACK flag set
int32 ACK_TIMEOUT = 50 # timeout waiting for an ack until we retry to send the message [ms]
int32 ACK_MAX_TRIES = 50 # maximum amount of tries to (re-)send a message, each time waiting ACK_TIMEOUT ms
uint64 timestamp # time since system start (microseconds)
int32 ACK_TIMEOUT = 50 # timeout waiting for an ack until we retry to send the message [ms]
int32 ACK_MAX_TRIES = 50 # maximum amount of tries to (re-)send a message, each time waiting ACK_TIMEOUT ms
uint16 sequence

1
msg/vehicle_air_data.msg

@ -1,3 +1,4 @@ @@ -1,3 +1,4 @@
uint64 timestamp # time since system start (microseconds)
float32 baro_alt_meter # Altitude above MSL calculated from temperature compensated baro sensor data using an ISA corrected for sea level pressure SENS_BARO_QNH.
float32 baro_temp_celcius # Temperature in degrees celsius

2
msg/vehicle_attitude.msg

@ -1,5 +1,7 @@ @@ -1,5 +1,7 @@
# This is similar to the mavlink message ATTITUDE_QUATERNION, but for onboard use
uint64 timestamp # time since system start (microseconds)
float32 rollspeed # Bias corrected angular velocity about X body axis in rad/s
float32 pitchspeed # Bias corrected angular velocity about Y body axis in rad/s
float32 yawspeed # Bias corrected angular velocity about Z body axis in rad/s

1
msg/vehicle_attitude_setpoint.msg

@ -1,3 +1,4 @@ @@ -1,3 +1,4 @@
uint64 timestamp # time since system start (microseconds)
int8 LANDING_GEAR_UP = 1 # landing gear up
int8 LANDING_GEAR_DOWN = -1 # landing gear down

37
msg/vehicle_command.msg

@ -1,3 +1,4 @@ @@ -1,3 +1,4 @@
uint64 timestamp # time since system start (microseconds)
uint16 VEHICLE_CMD_CUSTOM_0 = 0 # test command
uint16 VEHICLE_CMD_CUSTOM_1 = 1 # test command
@ -15,26 +16,26 @@ uint16 VEHICLE_CMD_NAV_ROI = 80 # Sets the region of interest (ROI) for a sen @@ -15,26 +16,26 @@ uint16 VEHICLE_CMD_NAV_ROI = 80 # Sets the region of interest (ROI) for a sen
uint16 VEHICLE_CMD_NAV_PATHPLANNING = 81 # Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal|
uint16 VEHICLE_CMD_NAV_VTOL_TAKEOFF = 84 # Takeoff from ground / hand and transition to fixed wing |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude|
uint16 VEHICLE_CMD_NAV_VTOL_LAND = 85 # Transition to MC and land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude|
uint16 VEHICLE_CMD_NAV_GUIDED_LIMITS = 90 # set limits for external control |timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout| absolute altitude min (in meters, AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit| absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit| horizontal move limit (in meters, AMSL) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit| Empty| Empty| Empty|
uint16 VEHICLE_CMD_NAV_GUIDED_MASTER = 91 # set id of master controller |System ID| Component ID| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_NAV_GUIDED_ENABLE = 92 # hand control over to an external controller |On / Off (> 0.5f on)| Empty| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_NAV_GUIDED_LIMITS = 90 # set limits for external control |timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout| absolute altitude min (in meters, AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit| absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit| horizontal move limit (in meters, AMSL) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit| Empty| Empty| Empty|
uint16 VEHICLE_CMD_NAV_GUIDED_MASTER = 91 # set id of master controller |System ID| Component ID| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_NAV_GUIDED_ENABLE = 92 # hand control over to an external controller |On / Off (> 0.5f on)| Empty| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_NAV_DELAY = 93 # Delay the next navigation command a number of seconds or until a specified time |Delay in seconds (decimal, -1 to enable time-of-day fields)| hour (24h format, UTC, -1 to ignore)| minute (24h format, UTC, -1 to ignore)| second (24h format, UTC)| Empty| Empty| Empty|
uint16 VEHICLE_CMD_NAV_LAST = 95 # NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_CONDITION_DELAY = 112 # Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_CONDITION_CHANGE_ALT = 113 # Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude|
uint16 VEHICLE_CMD_CONDITION_DISTANCE = 114 # Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_CONDITION_YAW = 115 # Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty|
uint16 VEHICLE_CMD_CONDITION_LAST = 159 # NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_SET_MODE = 176 # Set system mode. |Mode, as defined by ENUM MAV_MODE| Empty| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_JUMP = 177 # Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_CHANGE_SPEED = 178 # Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed)| Speed (m/s, -1 indicates no change)| Throttle ( Percent, -1 indicates no change)| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_SET_HOME = 179 # Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Empty| Latitude| Longitude| Altitude|
uint16 VEHICLE_CMD_DO_SET_PARAMETER = 180 # Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. |Parameter number| Parameter value| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_SET_RELAY = 181 # Set a relay to a condition. |Relay number| Setting (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_REPEAT_RELAY = 182 # Cycle a relay on and off for a desired number of cyles with a desired period. |Relay number| Cycle count| Cycle time (seconds, decimal)| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_SET_SERVO = 183 # Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_REPEAT_SERVO = 184 # Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_FLIGHTTERMINATION = 185 # Terminate flight immediately |Flight termination activated if > 0.5| Empty| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_CONDITION_DELAY = 112 # Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_CONDITION_CHANGE_ALT = 113 # Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude|
uint16 VEHICLE_CMD_CONDITION_DISTANCE = 114 # Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_CONDITION_YAW = 115 # Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty|
uint16 VEHICLE_CMD_CONDITION_LAST = 159 # NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_SET_MODE = 176 # Set system mode. |Mode, as defined by ENUM MAV_MODE| Empty| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_JUMP = 177 # Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_CHANGE_SPEED = 178 # Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed)| Speed (m/s, -1 indicates no change)| Throttle ( Percent, -1 indicates no change)| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_SET_HOME = 179 # Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Empty| Latitude| Longitude| Altitude|
uint16 VEHICLE_CMD_DO_SET_PARAMETER = 180 # Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. |Parameter number| Parameter value| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_SET_RELAY = 181 # Set a relay to a condition. |Relay number| Setting (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_REPEAT_RELAY = 182 # Cycle a relay on and off for a desired number of cyles with a desired period. |Relay number| Cycle count| Cycle time (seconds, decimal)| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_SET_SERVO = 183 # Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_REPEAT_SERVO = 184 # Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_FLIGHTTERMINATION = 185 # Terminate flight immediately |Flight termination activated if > 0.5| Empty| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_LAND_START = 189 # Mission command to perform a landing. This is used as a marker in a mission to tell the autopilot where a sequence of mission items that represents a landing starts. It may also be sent via a COMMAND_LONG to trigger a landing, in which case the nearest (geographically) landing sequence in the mission will be used. The Latitude/Longitude is optional, and may be set to 0/0 if not needed. If specified then it will be used to help find the closest landing sequence. |Empty| Empty| Empty| Empty| Latitude| Longitude| Empty| */
uint16 VEHICLE_CMD_DO_GO_AROUND = 191 # Mission command to safely abort an autonmous landing. |Altitude (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */
uint16 VEHICLE_CMD_DO_REPOSITION = 192

1
msg/vehicle_command_ack.msg

@ -1,3 +1,4 @@ @@ -1,3 +1,4 @@
uint64 timestamp # time since system start (microseconds)
uint8 VEHICLE_RESULT_ACCEPTED = 0
uint8 VEHICLE_RESULT_TEMPORARILY_REJECTED = 1
uint8 VEHICLE_RESULT_DENIED = 2

2
msg/vehicle_constraints.msg

@ -1,6 +1,8 @@ @@ -1,6 +1,8 @@
# Local setpoint constraints in NED frame
# setting something to NaN means that no limit is provided
uint64 timestamp # time since system start (microseconds)
float32 yawspeed # in radians/sec
float32 speed_xy # in meters/sec
float32 speed_up # in meters/sec

6
msg/vehicle_control_mode.msg

@ -1,7 +1,5 @@ @@ -1,7 +1,5 @@
# is set whenever the writing thread stores new data
bool flag_armed
uint64 timestamp # time since system start (microseconds)
bool flag_armed # is set whenever the writing thread stores new data
bool flag_external_manual_override_ok # external override non-fatal for system. Only true for fixed wing

2
msg/vehicle_global_position.msg

@ -5,6 +5,8 @@ @@ -5,6 +5,8 @@
# e.g. control inputs of the vehicle in a Kalman-filter implementation.
#
uint64 timestamp # time since system start (microseconds)
float64 lat # Latitude, (degrees)
float64 lon # Longitude, (degrees)
float32 alt # Altitude AMSL, (meters)

24
msg/vehicle_gps_position.msg

@ -1,13 +1,15 @@ @@ -1,13 +1,15 @@
# GPS position in WGS84 coordinates.
# the auto-generated field 'timestamp' is for the position & velocity (microseconds)
# the field 'timestamp' is for the position & velocity (microseconds)
uint64 timestamp # time since system start (microseconds)
int32 lat # Latitude in 1E-7 degrees
int32 lon # Longitude in 1E-7 degrees
int32 lon # Longitude in 1E-7 degrees
int32 alt # Altitude in 1E-3 meters above MSL, (millimetres)
int32 alt_ellipsoid # Altitude in 1E-3 meters bove Ellipsoid, (millimetres)
float32 s_variance_m_s # GPS speed accuracy estimate, (metres/sec)
float32 c_variance_rad # GPS course accuracy estimate, (radians)
uint8 fix_type # 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: RTCM code differential, 5: Real-Time Kinematic, float, 6: Real-Time Kinematic, fixed, 8: Extrapolated. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
float32 c_variance_rad # GPS course accuracy estimate, (radians)
uint8 fix_type # 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: RTCM code differential, 5: Real-Time Kinematic, float, 6: Real-Time Kinematic, fixed, 8: Extrapolated. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
float32 eph # GPS horizontal position accuracy (metres)
float32 epv # GPS vertical position accuracy (metres)
@ -18,16 +20,16 @@ float32 vdop # Vertical dilution of precision @@ -18,16 +20,16 @@ float32 vdop # Vertical dilution of precision
int32 noise_per_ms # GPS noise per millisecond
int32 jamming_indicator # indicates jamming is occurring
float32 vel_m_s # GPS ground speed, (metres/sec)
float32 vel_n_m_s # GPS North velocity, (metres/sec)
float32 vel_m_s # GPS ground speed, (metres/sec)
float32 vel_n_m_s # GPS North velocity, (metres/sec)
float32 vel_e_m_s # GPS East velocity, (metres/sec)
float32 vel_d_m_s # GPS Down velocity, (metres/sec)
float32 cog_rad # Course over ground (NOT heading, but direction of movement), -PI..PI, (radians)
bool vel_ned_valid # True if NED velocity is valid
float32 vel_d_m_s # GPS Down velocity, (metres/sec)
float32 cog_rad # Course over ground (NOT heading, but direction of movement), -PI..PI, (radians)
bool vel_ned_valid # True if NED velocity is valid
int32 timestamp_time_relative # timestamp + timestamp_time_relative = Time of the UTC timestamp since system start, (microseconds)
uint64 time_utc_usec # Timestamp (microseconds, UTC), this is the timestamp which comes from the gps module. It might be unavailable right after cold start, indicated by a value of 0
uint64 time_utc_usec # Timestamp (microseconds, UTC), this is the timestamp which comes from the gps module. It might be unavailable right after cold start, indicated by a value of 0
uint8 satellites_used # Number of satellites used
uint8 satellites_used # Number of satellites used
float32 heading # heading in NED. Set to NaN if not set (used for dual antenna GPS), (rad, [-PI, PI])

1
msg/vehicle_land_detected.msg

@ -1,3 +1,4 @@ @@ -1,3 +1,4 @@
uint64 timestamp # time since system start (microseconds)
bool landed # true if vehicle is currently landed on the ground
bool freefall # true if vehicle is currently in free-fall
bool ground_contact # true if vehicle has ground contact but is not landed

4
msg/vehicle_local_position.msg

@ -1,5 +1,7 @@ @@ -1,5 +1,7 @@
# Fused local position in NED.
uint64 timestamp # time since system start (microseconds)
bool xy_valid # true if x and y are valid
bool z_valid # true if z is valid
bool v_xy_valid # true if vy and vy are valid
@ -35,7 +37,7 @@ float32 ay # East velocity derivative in NED earth-fixed frame, (metres/s @@ -35,7 +37,7 @@ float32 ay # East velocity derivative in NED earth-fixed frame, (metres/s
float32 az # Down velocity derivative in NED earth-fixed frame, (metres/sec^2)
# Heading
float32 yaw # Euler yaw angle transforming the tangent plane relative to NED earth-fixed frame, -PI..+PI, (radians)
float32 yaw # Euler yaw angle transforming the tangent plane relative to NED earth-fixed frame, -PI..+PI, (radians)
# Position of reference point (local NED frame origin) in global (GPS / WGS84) frame
bool xy_global # true if position (x, y) has a valid global reference (ref_lat, ref_lon)

2
msg/vehicle_local_position_setpoint.msg

@ -1,6 +1,8 @@ @@ -1,6 +1,8 @@
# Local position setpoint in NED frame
# setting something to NaN means the state should not be controlled
uint64 timestamp # time since system start (microseconds)
float32 x # in meters NED
float32 y # in meters NED
float32 z # in meters NED

1
msg/vehicle_magnetometer.msg

@ -1,2 +1,3 @@ @@ -1,2 +1,3 @@
uint64 timestamp # time since system start (microseconds)
float32[3] magnetometer_ga # Magnetic field in NED body frame, in Gauss

Some files were not shown because too many files have changed in this diff Show More

Loading…
Cancel
Save