diff --git a/msg/actuator_armed.msg b/msg/actuator_armed.msg index f44ea729c2..98aa90e7e3 100644 --- a/msg/actuator_armed.msg +++ b/msg/actuator_armed.msg @@ -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 diff --git a/msg/actuator_controls.msg b/msg/actuator_controls.msg index 46bf35ebff..d266f25bea 100644 --- a/msg/actuator_controls.msg +++ b/msg/actuator_controls.msg @@ -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 # TOPICS actuator_controls actuator_controls_0 actuator_controls_1 actuator_controls_2 actuator_controls_3 # TOPICS actuator_controls_virtual_fw actuator_controls_virtual_mc - diff --git a/msg/actuator_direct.msg b/msg/actuator_direct.msg index 7d22f79e75..007745e90b 100644 --- a/msg/actuator_direct.msg +++ b/msg/actuator_direct.msg @@ -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 diff --git a/msg/actuator_outputs.msg b/msg/actuator_outputs.msg index 269255340d..57fc215e00 100644 --- a/msg/actuator_outputs.msg +++ b/msg/actuator_outputs.msg @@ -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 diff --git a/msg/adc_report.msg b/msg/adc_report.msg index 7d43562dc5..b4eca08b43 100644 --- a/msg/adc_report.msg +++ b/msg/adc_report.msg @@ -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 diff --git a/msg/airspeed.msg b/msg/airspeed.msg index 74b2745be2..0b9524844f 100644 --- a/msg/airspeed.msg +++ b/msg/airspeed.msg @@ -1,3 +1,4 @@ +uint64 timestamp # time since system start (microseconds) float32 indicated_airspeed_m_s # indicated airspeed in m/s diff --git a/msg/att_pos_mocap.msg b/msg/att_pos_mocap.msg index 6c007a6393..3651697036 100644 --- a/msg/att_pos_mocap.msg +++ b/msg/att_pos_mocap.msg @@ -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 diff --git a/msg/battery_status.msg b/msg/battery_status.msg index c366841966..1690eb654b 100644 --- a/msg/battery_status.msg +++ b/msg/battery_status.msg @@ -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 diff --git a/msg/camera_capture.msg b/msg/camera_capture.msg index 3f94a854d1..f4491ffefa 100644 --- a/msg/camera_capture.msg +++ b/msg/camera_capture.msg @@ -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) diff --git a/msg/camera_trigger.msg b/msg/camera_trigger.msg index b50d1a5a5e..5f937a7e5e 100644 --- a/msg/camera_trigger.msg +++ b/msg/camera_trigger.msg @@ -1,3 +1,4 @@ +uint64 timestamp # time since system start (microseconds) uint64 timestamp_utc # UTC timestamp uint32 seq # Image sequence number diff --git a/msg/collision_report.msg b/msg/collision_report.msg index 726c1fb786..1ad7ce7265 100644 --- a/msg/collision_report.msg +++ b/msg/collision_report.msg @@ -1,3 +1,4 @@ +uint64 timestamp # time since system start (microseconds) uint8 src uint32 id uint8 action diff --git a/msg/commander_state.msg b/msg/commander_state.msg index 00b5f1acac..9733d72a51 100644 --- a/msg/commander_state.msg +++ b/msg/commander_state.msg @@ -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 uint8 MAIN_STATE_AUTO_PRECLAND = 13 uint8 MAIN_STATE_MAX = 14 - uint8 main_state # main state machine diff --git a/msg/cpuload.msg b/msg/cpuload.msg index 9381c05e83..efc2c4df59 100644 --- a/msg/cpuload.msg +++ b/msg/cpuload.msg @@ -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 diff --git a/msg/debug_key_value.msg b/msg/debug_key_value.msg index 023531e038..6815811efb 100644 --- a/msg/debug_key_value.msg +++ b/msg/debug_key_value.msg @@ -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 diff --git a/msg/debug_value.msg b/msg/debug_value.msg index d8d3bfd8ff..8be1312473 100644 --- a/msg/debug_value.msg +++ b/msg/debug_value.msg @@ -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 diff --git a/msg/debug_vect.msg b/msg/debug_vect.msg index 2088a6f619..9c22e1dac3 100644 --- a/msg/debug_vect.msg +++ b/msg/debug_vect.msg @@ -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 diff --git a/msg/differential_pressure.msg b/msg/differential_pressure.msg index fff2a6da50..bfb8f85478 100644 --- a/msg/differential_pressure.msg +++ b/msg/differential_pressure.msg @@ -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 diff --git a/msg/distance_sensor.msg b/msg/distance_sensor.msg index 5e28cefab2..4a2e8f8d8f 100644 --- a/msg/distance_sensor.msg +++ b/msg/distance_sensor.msg @@ -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) diff --git a/msg/ekf2_innovations.msg b/msg/ekf2_innovations.msg index 85fd48b89f..90dd820a71 100644 --- a/msg/ekf2_innovations.msg +++ b/msg/ekf2_innovations.msg @@ -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 diff --git a/msg/ekf2_timestamps.msg b/msg/ekf2_timestamps.msg index 1700e827e7..5552ef2fe8 100644 --- a/msg/ekf2_timestamps.msg +++ b/msg/ekf2_timestamps.msg @@ -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 int16 vision_position_timestamp_rel # Note: this is a high-rate logged topic, so it needs to be as small as possible - diff --git a/msg/ekf_gps_position.msg b/msg/ekf_gps_position.msg index 1c0a3a4ec9..330852f282 100644 --- a/msg/ekf_gps_position.msg +++ b/msg/ekf_gps_position.msg @@ -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) diff --git a/msg/esc_report.msg b/msg/esc_report.msg index 8525f3be15..b2079f4fa2 100644 --- a/msg/esc_report.msg +++ b/msg/esc_report.msg @@ -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 diff --git a/msg/esc_status.msg b/msg/esc_status.msg index 5148642459..167bde5334 100644 --- a/msg/esc_status.msg +++ b/msg/esc_status.msg @@ -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 diff --git a/msg/estimator_status.msg b/msg/estimator_status.msg index 59ab6aa19d..cb8d645111 100644 --- a/msg/estimator_status.msg +++ b/msg/estimator_status.msg @@ -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 diff --git a/msg/follow_target.msg b/msg/follow_target.msg index 75f124e2ee..f0afe3f4b8 100644 --- a/msg/follow_target.msg +++ b/msg/follow_target.msg @@ -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 diff --git a/msg/fw_pos_ctrl_status.msg b/msg/fw_pos_ctrl_status.msg index 0af57b1bf5..cbd148b1e4 100644 --- a/msg/fw_pos_ctrl_status.msg +++ b/msg/fw_pos_ctrl_status.msg @@ -1,3 +1,4 @@ +uint64 timestamp # time since system start (microseconds) float32 nav_roll float32 nav_pitch float32 nav_bearing diff --git a/msg/geofence_result.msg b/msg/geofence_result.msg index 0daba4a4ac..25022bbd56 100644 --- a/msg/geofence_result.msg +++ b/msg/geofence_result.msg @@ -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 diff --git a/msg/gps_dump.msg b/msg/gps_dump.msg index 8a91149d46..3718e457cb 100644 --- a/msg/gps_dump.msg +++ b/msg/gps_dump.msg @@ -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 diff --git a/msg/gps_inject_data.msg b/msg/gps_inject_data.msg index ac44d02dbe..00b1aa1b8a 100644 --- a/msg/gps_inject_data.msg +++ b/msg/gps_inject_data.msg @@ -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) diff --git a/msg/home_position.msg b/msg/home_position.msg index 5515aadfb7..9d263dee04 100644 --- a/msg/home_position.msg +++ b/msg/home_position.msg @@ -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) diff --git a/msg/input_rc.msg b/msg/input_rc.msg index 1a7de29afd..05aa6034f3 100644 --- a/msg/input_rc.msg +++ b/msg/input_rc.msg @@ -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 diff --git a/msg/iridiumsbd_status.msg b/msg/iridiumsbd_status.msg index 1483ce5a80..75b167ffa4 100644 --- a/msg/iridiumsbd_status.msg +++ b/msg/iridiumsbd_status.msg @@ -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 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 \ No newline at end of file +bool rx_session_pending # indicates if a rx session is pending diff --git a/msg/irlock_report.msg b/msg/irlock_report.msg index ded99a2581..9f23cbf3ca 100644 --- a/msg/irlock_report.msg +++ b/msg/irlock_report.msg @@ -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. diff --git a/msg/landing_target_innovations.msg b/msg/landing_target_innovations.msg index 73286aa595..5dd892c560 100644 --- a/msg/landing_target_innovations.msg +++ b/msg/landing_target_innovations.msg @@ -1,3 +1,4 @@ +uint64 timestamp # time since system start (microseconds) # Innovation of landing target position estimator float32 innov_x float32 innov_y diff --git a/msg/landing_target_pose.msg b/msg/landing_target_pose.msg index 5a31fa953f..875920f183 100644 --- a/msg/landing_target_pose.msg +++ b/msg/landing_target_pose.msg @@ -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 diff --git a/msg/led_control.msg b/msg/led_control.msg index 1a0bb6f06b..582c9dfb73 100644 --- a/msg/led_control.msg +++ b/msg/led_control.msg @@ -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 diff --git a/msg/log_message.msg b/msg/log_message.msg index 51fcbbd50d..f0817520a9 100644 --- a/msg/log_message.msg +++ b/msg/log_message.msg @@ -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 - diff --git a/msg/manual_control_setpoint.msg b/msg/manual_control_setpoint.msg index 253aa327a8..392fc97105 100644 --- a/msg/manual_control_setpoint.msg +++ b/msg/manual_control_setpoint.msg @@ -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) diff --git a/msg/mavlink_log.msg b/msg/mavlink_log.msg index 274596adde..e089e30ea7 100644 --- a/msg/mavlink_log.msg +++ b/msg/mavlink_log.msg @@ -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) diff --git a/msg/mission.msg b/msg/mission.msg index c2fbaafabc..c8a51cc800 100644 --- a/msg/mission.msg +++ b/msg/mission.msg @@ -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 \ No newline at end of file +int32 current_seq # default -1, start at the one changed latest diff --git a/msg/mission_result.msg b/msg/mission_result.msg index edf0a0b16d..b53525f016 100644 --- a/msg/mission_result.msg +++ b/msg/mission_result.msg @@ -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 diff --git a/msg/mount_orientation.msg b/msg/mount_orientation.msg index 9d068bd168..7a270c3ae7 100644 --- a/msg/mount_orientation.msg +++ b/msg/mount_orientation.msg @@ -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 diff --git a/msg/multirotor_motor_limits.msg b/msg/multirotor_motor_limits.msg index ba6c8f3de0..2cd692fd36 100644 --- a/msg/multirotor_motor_limits.msg +++ b/msg/multirotor_motor_limits.msg @@ -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 diff --git a/msg/obstacle_distance.msg b/msg/obstacle_distance.msg index a2cf3f968c..1e2b017243 100644 --- a/msg/obstacle_distance.msg +++ b/msg/obstacle_distance.msg @@ -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 diff --git a/msg/offboard_control_mode.msg b/msg/offboard_control_mode.msg index eaff918152..ab55684ec6 100644 --- a/msg/offboard_control_mode.msg +++ b/msg/offboard_control_mode.msg @@ -1,5 +1,7 @@ # Off-board control mode +uint64 timestamp # time since system start (microseconds) + bool ignore_thrust bool ignore_attitude bool ignore_bodyrate diff --git a/msg/optical_flow.msg b/msg/optical_flow.msg index de418511eb..6c0a90bed0 100644 --- a/msg/optical_flow.msg +++ b/msg/optical_flow.msg @@ -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 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 \ No newline at end of file +float32 max_ground_distance # Maximum distance from ground at which the optical flow sensor operates reliably diff --git a/msg/parameter_update.msg b/msg/parameter_update.msg index d7e88320f0..105a8dd711 100644 --- a/msg/parameter_update.msg +++ b/msg/parameter_update.msg @@ -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 diff --git a/msg/ping.msg b/msg/ping.msg index c839e2bb3a..498a3c73f3 100644 --- a/msg/ping.msg +++ b/msg/ping.msg @@ -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 diff --git a/msg/position_setpoint.msg b/msg/position_setpoint.msg index 29a83ed715..42e77c8761 100644 --- a/msg/position_setpoint.msg +++ b/msg/position_setpoint.msg @@ -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 diff --git a/msg/position_setpoint_triplet.msg b/msg/position_setpoint_triplet.msg index 51ac92dfdf..7c9a2ca78b 100644 --- a/msg/position_setpoint_triplet.msg +++ b/msg/position_setpoint_triplet.msg @@ -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 diff --git a/msg/power_button_state.msg b/msg/power_button_state.msg index b941aa820c..1518066633 100644 --- a/msg/power_button_state.msg +++ b/msg/power_button_state.msg @@ -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 diff --git a/msg/pwm_input.msg b/msg/pwm_input.msg index 8b91883532..40b5429b79 100644 --- a/msg/pwm_input.msg +++ b/msg/pwm_input.msg @@ -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 diff --git a/msg/qshell_req.msg b/msg/qshell_req.msg index 478d1e7028..448a2b12b8 100644 --- a/msg/qshell_req.msg +++ b/msg/qshell_req.msg @@ -1,3 +1,4 @@ +uint64 timestamp # time since system start (microseconds) uint8[100] cmd uint32 MAX_STRLEN = 100 uint32 strlen diff --git a/msg/qshell_retval.msg b/msg/qshell_retval.msg index f51d16ea7f..c8c56fd728 100644 --- a/msg/qshell_retval.msg +++ b/msg/qshell_retval.msg @@ -1,2 +1,3 @@ +uint64 timestamp # time since system start (microseconds) int32 return_value uint32 sequence diff --git a/msg/rate_ctrl_status.msg b/msg/rate_ctrl_status.msg index 0e28ede022..01008d54c5 100644 --- a/msg/rate_ctrl_status.msg +++ b/msg/rate_ctrl_status.msg @@ -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 diff --git a/msg/rc_channels.msg b/msg/rc_channels.msg index 6d31e9d5a8..eef6064ed7 100644 --- a/msg/rc_channels.msg +++ b/msg/rc_channels.msg @@ -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 diff --git a/msg/rc_parameter_map.msg b/msg/rc_parameter_map.msg index 4a5cb5cfd1..2a5df3e74b 100644 --- a/msg/rc_parameter_map.msg +++ b/msg/rc_parameter_map.msg @@ -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 diff --git a/msg/safety.msg b/msg/safety.msg index d69f12509e..62046c71b7 100644 --- a/msg/safety.msg +++ b/msg/safety.msg @@ -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 diff --git a/msg/satellite_info.msg b/msg/satellite_info.msg index 0efa030a87..2192bd3e32 100644 --- a/msg/satellite_info.msg +++ b/msg/satellite_info.msg @@ -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 diff --git a/msg/sensor_accel.msg b/msg/sensor_accel.msg index e0648cda00..ce49dd1d4b 100644 --- a/msg/sensor_accel.msg +++ b/msg/sensor_accel.msg @@ -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 diff --git a/msg/sensor_baro.msg b/msg/sensor_baro.msg index c1b986087a..ff1cd498b8 100644 --- a/msg/sensor_baro.msg +++ b/msg/sensor_baro.msg @@ -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 diff --git a/msg/sensor_bias.msg b/msg/sensor_bias.msg index a3801903cf..29a14cb083 100644 --- a/msg/sensor_bias.msg +++ b/msg/sensor_bias.msg @@ -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) diff --git a/msg/sensor_combined.msg b/msg/sensor_combined.msg index 4d1040747b..2d47064f00 100644 --- a/msg/sensor_combined.msg +++ b/msg/sensor_combined.msg @@ -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 diff --git a/msg/sensor_correction.msg b/msg/sensor_correction.msg index 2529a53240..4f2fb10d99 100644 --- a/msg/sensor_correction.msg +++ b/msg/sensor_correction.msg @@ -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 diff --git a/msg/sensor_gyro.msg b/msg/sensor_gyro.msg index e5395a5092..5a7ec71d78 100644 --- a/msg/sensor_gyro.msg +++ b/msg/sensor_gyro.msg @@ -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 diff --git a/msg/sensor_mag.msg b/msg/sensor_mag.msg index c79bd2430c..7e02b35ba0 100644 --- a/msg/sensor_mag.msg +++ b/msg/sensor_mag.msg @@ -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 diff --git a/msg/sensor_preflight.msg b/msg/sensor_preflight.msg index 293953f886..c820595377 100644 --- a/msg/sensor_preflight.msg +++ b/msg/sensor_preflight.msg @@ -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). diff --git a/msg/sensor_selection.msg b/msg/sensor_selection.msg index c6141f0690..1ccde7895a 100644 --- a/msg/sensor_selection.msg +++ b/msg/sensor_selection.msg @@ -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 diff --git a/msg/servorail_status.msg b/msg/servorail_status.msg index 39edf80e4f..36a25ece52 100644 --- a/msg/servorail_status.msg +++ b/msg/servorail_status.msg @@ -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 diff --git a/msg/subsystem_info.msg b/msg/subsystem_info.msg index a08d85abb3..37eaca5e94 100644 --- a/msg/subsystem_info.msg +++ b/msg/subsystem_info.msg @@ -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 diff --git a/msg/system_power.msg b/msg/system_power.msg index 332befc0e2..f0d5d2f861 100644 --- a/msg/system_power.msg +++ b/msg/system_power.msg @@ -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. diff --git a/msg/task_stack_info.msg b/msg/task_stack_info.msg index 1dea74211e..3f0f29dce0 100644 --- a/msg/task_stack_info.msg +++ b/msg/task_stack_info.msg @@ -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 diff --git a/msg/tecs_status.msg b/msg/tecs_status.msg index 8b3ce5ed48..45e33a261d 100644 --- a/msg/tecs_status.msg +++ b/msg/tecs_status.msg @@ -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 diff --git a/msg/telemetry_status.msg b/msg/telemetry_status.msg index 7232102410..4424fb9a74 100644 --- a/msg/telemetry_status.msg +++ b/msg/telemetry_status.msg @@ -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 diff --git a/msg/templates/uorb/msg.cpp.template b/msg/templates/uorb/msg.cpp.template index d803e34f30..cbb6d696e4 100644 --- a/msg/templates/uorb/msg.cpp.template +++ b/msg/templates/uorb/msg.cpp.template @@ -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 diff --git a/msg/templates/uorb/msg.h.template b/msg/templates/uorb/msg.h.template index e150640f2c..a5d1e9c102 100644 --- a/msg/templates/uorb/msg.h.template +++ b/msg/templates/uorb/msg.h.template @@ -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 diff --git a/msg/templates/uorb_microcdr/msg.cpp.template b/msg/templates/uorb_microcdr/msg.cpp.template index 60fd383aa4..281a58311d 100644 --- a/msg/templates/uorb_microcdr/msg.cpp.template +++ b/msg/templates/uorb_microcdr/msg.cpp.template @@ -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 reset_micro_buffer(microCDRReader); - deserialize_uint64_t(microCDRReader, &output->timestamp); @add_code_to_deserialize() } diff --git a/msg/templates/urtps/msg.idl.template b/msg/templates/urtps/msg.idl.template index 8e30eaebc7..5430ecaea6 100644 --- a/msg/templates/urtps/msg.idl.template +++ b/msg/templates/urtps/msg.idl.template @@ -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)_ diff --git a/msg/test_motor.msg b/msg/test_motor.msg index 2805fa64f5..eaad0d74e7 100644 --- a/msg/test_motor.msg +++ b/msg/test_motor.msg @@ -1,3 +1,4 @@ +uint64 timestamp # time since system start (microseconds) uint8 NUM_MOTOR_OUTPUTS = 8 uint32 motor_number # number of motor to spin diff --git a/msg/timesync_status.msg b/msg/timesync_status.msg index 1ae9adf581..38ff31db75 100644 --- a/msg/timesync_status.msg +++ b/msg/timesync_status.msg @@ -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) \ No newline at end of file +uint32 round_trip_time # round trip time of this timesync packet (microseconds) diff --git a/msg/trajectory_waypoint.msg b/msg/trajectory_waypoint.msg index e23998ce59..22d222423a 100644 --- a/msg/trajectory_waypoint.msg +++ b/msg/trajectory_waypoint.msg @@ -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 diff --git a/msg/transponder_report.msg b/msg/transponder_report.msg index 8ff35d1e40..603f034fa4 100644 --- a/msg/transponder_report.msg +++ b/msg/transponder_report.msg @@ -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 diff --git a/msg/tune_control.msg b/msg/tune_control.msg index ef83311c52..3820c239d9 100644 --- a/msg/tune_control.msg +++ b/msg/tune_control.msg @@ -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 diff --git a/msg/uavcan_parameter_request.msg b/msg/uavcan_parameter_request.msg index 9ced52bbae..e6e480ebd4 100644 --- a/msg/uavcan_parameter_request.msg +++ b/msg/uavcan_parameter_request.msg @@ -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 diff --git a/msg/uavcan_parameter_value.msg b/msg/uavcan_parameter_value.msg index 091c5fd278..8eff663a57 100644 --- a/msg/uavcan_parameter_value.msg +++ b/msg/uavcan_parameter_value.msg @@ -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 diff --git a/msg/ulog_stream.msg b/msg/ulog_stream.msg index 446d8c1d70..8dc7a1c572 100644 --- a/msg/ulog_stream.msg +++ b/msg/ulog_stream.msg @@ -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 uint16 sequence # allows determine drops uint8 flags # see FLAGS_* uint8[249] data # ulog data - diff --git a/msg/ulog_stream_ack.msg b/msg/ulog_stream_ack.msg index b293f5c496..363d0804de 100644 --- a/msg/ulog_stream_ack.msg +++ b/msg/ulog_stream_ack.msg @@ -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 diff --git a/msg/vehicle_air_data.msg b/msg/vehicle_air_data.msg index ef2246691d..85c15322a7 100644 --- a/msg/vehicle_air_data.msg +++ b/msg/vehicle_air_data.msg @@ -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 diff --git a/msg/vehicle_attitude.msg b/msg/vehicle_attitude.msg index 4504da967d..24e17d00a5 100644 --- a/msg/vehicle_attitude.msg +++ b/msg/vehicle_attitude.msg @@ -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 diff --git a/msg/vehicle_attitude_setpoint.msg b/msg/vehicle_attitude_setpoint.msg index 5cb14b3855..441774bdb1 100644 --- a/msg/vehicle_attitude_setpoint.msg +++ b/msg/vehicle_attitude_setpoint.msg @@ -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 diff --git a/msg/vehicle_command.msg b/msg/vehicle_command.msg index 60109da81f..28bfb6e01d 100644 --- a/msg/vehicle_command.msg +++ b/msg/vehicle_command.msg @@ -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 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 diff --git a/msg/vehicle_command_ack.msg b/msg/vehicle_command_ack.msg index 0fd93e6fa3..0f7d291774 100644 --- a/msg/vehicle_command_ack.msg +++ b/msg/vehicle_command_ack.msg @@ -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 diff --git a/msg/vehicle_constraints.msg b/msg/vehicle_constraints.msg index 5acffd0d80..40dd755027 100644 --- a/msg/vehicle_constraints.msg +++ b/msg/vehicle_constraints.msg @@ -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 diff --git a/msg/vehicle_control_mode.msg b/msg/vehicle_control_mode.msg index 2a3e789a91..2e6c922b0d 100644 --- a/msg/vehicle_control_mode.msg +++ b/msg/vehicle_control_mode.msg @@ -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 diff --git a/msg/vehicle_global_position.msg b/msg/vehicle_global_position.msg index a4cc03f169..766c3db453 100644 --- a/msg/vehicle_global_position.msg +++ b/msg/vehicle_global_position.msg @@ -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) diff --git a/msg/vehicle_gps_position.msg b/msg/vehicle_gps_position.msg index 48ff70ebee..acb0c46a96 100644 --- a/msg/vehicle_gps_position.msg +++ b/msg/vehicle_gps_position.msg @@ -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 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]) diff --git a/msg/vehicle_land_detected.msg b/msg/vehicle_land_detected.msg index 387d18f0eb..9082e7b184 100644 --- a/msg/vehicle_land_detected.msg +++ b/msg/vehicle_land_detected.msg @@ -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 diff --git a/msg/vehicle_local_position.msg b/msg/vehicle_local_position.msg index 1d2971bb55..e0550feedb 100644 --- a/msg/vehicle_local_position.msg +++ b/msg/vehicle_local_position.msg @@ -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 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) diff --git a/msg/vehicle_local_position_setpoint.msg b/msg/vehicle_local_position_setpoint.msg index e44175d767..3222bbb027 100644 --- a/msg/vehicle_local_position_setpoint.msg +++ b/msg/vehicle_local_position_setpoint.msg @@ -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 diff --git a/msg/vehicle_magnetometer.msg b/msg/vehicle_magnetometer.msg index c675cb58df..bb0146c724 100644 --- a/msg/vehicle_magnetometer.msg +++ b/msg/vehicle_magnetometer.msg @@ -1,2 +1,3 @@ +uint64 timestamp # time since system start (microseconds) float32[3] magnetometer_ga # Magnetic field in NED body frame, in Gauss diff --git a/msg/vehicle_rates_setpoint.msg b/msg/vehicle_rates_setpoint.msg index 13fd4d4b6c..e40768b3fe 100644 --- a/msg/vehicle_rates_setpoint.msg +++ b/msg/vehicle_rates_setpoint.msg @@ -1,3 +1,4 @@ +uint64 timestamp # time since system start (microseconds) float32 roll # body angular rates in NED frame float32 pitch # body angular rates in NED frame diff --git a/msg/vehicle_roi.msg b/msg/vehicle_roi.msg index ebb3f5b4f9..4fe9f6b54e 100644 --- a/msg/vehicle_roi.msg +++ b/msg/vehicle_roi.msg @@ -1,5 +1,7 @@ # Vehicle Region Of Interest (ROI) +uint64 timestamp # time since system start (microseconds) + uint8 ROI_NONE = 0 # No region of interest uint8 ROI_WPNEXT = 1 # Point toward next MISSION with optional offset uint8 ROI_WPINDEX = 2 # Point toward given MISSION @@ -17,4 +19,3 @@ float32 alt # Altitude to point to float32 roll_offset # angle offset in rad float32 pitch_offset # angle offset in rad float32 yaw_offset # angle offset in rad - diff --git a/msg/vehicle_status.msg b/msg/vehicle_status.msg index b49e1f8eba..f0b61a0529 100644 --- a/msg/vehicle_status.msg +++ b/msg/vehicle_status.msg @@ -1,5 +1,7 @@ # If you change the order, add or remove arming_state_t states make sure to update the arrays # in state_machine_helper.cpp as well. +uint64 timestamp # time since system start (microseconds) + uint8 ARMING_STATE_INIT = 0 uint8 ARMING_STATE_STANDBY = 1 uint8 ARMING_STATE_ARMED = 2 diff --git a/msg/vehicle_status_flags.msg b/msg/vehicle_status_flags.msg index 30514aa1a1..6bc4235aab 100644 --- a/msg/vehicle_status_flags.msg +++ b/msg/vehicle_status_flags.msg @@ -1,5 +1,7 @@ # This is a struct used by the commander internally. +uint64 timestamp # time since system start (microseconds) + bool condition_calibration_enabled bool condition_system_sensors_initialized bool condition_system_hotplug_timeout # true if the hotplug sensor search is over diff --git a/msg/vehicle_trajectory_waypoint.msg b/msg/vehicle_trajectory_waypoint.msg index fe712a11ca..f30160a373 100644 --- a/msg/vehicle_trajectory_waypoint.msg +++ b/msg/vehicle_trajectory_waypoint.msg @@ -2,6 +2,8 @@ # The topic vehicle_trajectory_waypoint_desired is used to send the user desired waypoints from the position controller to the companion computer / avoidance module. # The topic vehicle_trajectory_waypoint is used to send the adjusted waypoints from the companion computer / avoidance module to the position controller. +uint64 timestamp # time since system start (microseconds) + uint8 MAV_TRAJECTORY_REPRESENTATION_WAYPOINTS = 0 uint8 type # Type from MAV_TRAJECTORY_REPRESENTATION enum. @@ -16,4 +18,4 @@ uint8 NUMBER_POINTS = 5 trajectory_waypoint[5] waypoints -# TOPICS vehicle_trajectory_waypoint vehicle_trajectory_waypoint_desired \ No newline at end of file +# TOPICS vehicle_trajectory_waypoint vehicle_trajectory_waypoint_desired diff --git a/msg/vtol_vehicle_status.msg b/msg/vtol_vehicle_status.msg index 1efece610f..54f9d1e5e2 100644 --- a/msg/vtol_vehicle_status.msg +++ b/msg/vtol_vehicle_status.msg @@ -5,6 +5,8 @@ uint8 VEHICLE_VTOL_STATE_TRANSITION_TO_MC = 2 uint8 VEHICLE_VTOL_STATE_MC = 3 uint8 VEHICLE_VTOL_STATE_FW = 4 +uint64 timestamp # time since system start (microseconds) + bool vtol_in_rw_mode # true: vtol vehicle is in rotating wing mode bool vtol_in_trans_mode bool in_transition_to_fw # True if VTOL is doing a transition from MC to FW diff --git a/msg/wind_estimate.msg b/msg/wind_estimate.msg index ce69281a2c..636ca70592 100644 --- a/msg/wind_estimate.msg +++ b/msg/wind_estimate.msg @@ -1,3 +1,4 @@ +uint64 timestamp # time since system start (microseconds) float32 windspeed_north # Wind component in north / X direction (m/sec) float32 windspeed_east # Wind component in east / Y direction (m/sec) diff --git a/src/examples/px4_mavlink_debug/px4_mavlink_debug.c b/src/examples/px4_mavlink_debug/px4_mavlink_debug.c index 69b095093d..1d746e45a2 100644 --- a/src/examples/px4_mavlink_debug/px4_mavlink_debug.c +++ b/src/examples/px4_mavlink_debug/px4_mavlink_debug.c @@ -77,19 +77,19 @@ int px4_mavlink_debug_main(int argc, char *argv[]) /* send one named value */ dbg_key.value = value_counter; - dbg_key.timestamp_ms = timestamp_ms; + dbg_key.timestamp = timestamp_ms * 1e3f; orb_publish(ORB_ID(debug_key_value), pub_dbg_key, &dbg_key); /* send one indexed value */ dbg_ind.value = 0.5f * value_counter; - dbg_ind.timestamp_ms = timestamp_ms; + dbg_ind.timestamp = timestamp_ms * 1e3f; orb_publish(ORB_ID(debug_value), pub_dbg_ind, &dbg_ind); /* send one vector */ dbg_vect.x = 1.0f * value_counter; dbg_vect.y = 2.0f * value_counter; dbg_vect.z = 3.0f * value_counter; - dbg_vect.timestamp_us = timestamp_us; + dbg_vect.timestamp = timestamp_us; orb_publish(ORB_ID(debug_vect), pub_dbg_vect, &dbg_vect); warnx("sent one more value.."); diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index 6f5a4dd214..00596fa401 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -3484,7 +3484,7 @@ protected: if (_debug_sub->update(&_debug_time, &debug)) { mavlink_named_value_float_t msg = {}; - msg.time_boot_ms = debug.timestamp_ms; + msg.time_boot_ms = debug.timestamp * 1e-3f; memcpy(msg.name, debug.key, sizeof(msg.name)); /* enforce null termination */ msg.name[sizeof(msg.name) - 1] = '\0'; @@ -3553,7 +3553,7 @@ protected: if (_debug_sub->update(&_debug_time, &debug)) { mavlink_debug_t msg = {}; - msg.time_boot_ms = debug.timestamp_ms; + msg.time_boot_ms = debug.timestamp * 1e-3f; msg.ind = debug.ind; msg.value = debug.value; @@ -3620,7 +3620,7 @@ protected: if (_debug_sub->update(&_debug_time, &debug)) { mavlink_debug_vect_t msg = {}; - msg.time_usec = debug.timestamp_us; + msg.time_usec = debug.timestamp; memcpy(msg.name, debug.name, sizeof(msg.name)); /* enforce null termination */ msg.name[sizeof(msg.name) - 1] = '\0'; diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index ba2acd93e0..0cf580117e 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -670,7 +670,7 @@ MavlinkReceiver::handle_message_optical_flow_rad(mavlink_message_t *msg) struct optical_flow_s f = {}; - f.timestamp = flow.time_usec; + f.timestamp = _mavlink_timesync.sync_stamp(flow.time_usec); f.integration_timespan = flow.integration_time_us; f.pixel_flow_x_integral = flow.integrated_x; f.pixel_flow_y_integral = flow.integrated_y; @@ -699,7 +699,7 @@ MavlinkReceiver::handle_message_optical_flow_rad(mavlink_message_t *msg) struct distance_sensor_s d = {}; if (flow.distance > 0.0f) { // negative values signal invalid data - d.timestamp = flow.integration_time_us * 1000; /* ms to us */ + d.timestamp = _mavlink_timesync.sync_stamp(flow.integration_time_us * 1000); /* ms to us */ d.min_distance = 0.3f; d.max_distance = 5.0f; d.current_distance = flow.distance; /* both are in m */ @@ -908,7 +908,7 @@ MavlinkReceiver::handle_message_set_position_target_local_ned(mavlink_message_t bool is_loiter_sp = (bool)(set_position_target_local_ned.type_mask & 0x3000); bool is_idle_sp = (bool)(set_position_target_local_ned.type_mask & 0x4000); - offboard_control_mode.timestamp = hrt_absolute_time(); + offboard_control_mode.timestamp = _mavlink_timesync.sync_stamp(set_position_target_local_ned.time_boot_ms * 1e3f); if (_offboard_control_mode_pub == nullptr) { _offboard_control_mode_pub = orb_advertise(ORB_ID(offboard_control_mode), &offboard_control_mode); @@ -936,7 +936,7 @@ MavlinkReceiver::handle_message_set_position_target_local_ned(mavlink_message_t } else { /* It's not a pure force setpoint: publish to setpoint triplet topic */ struct position_setpoint_triplet_s pos_sp_triplet = {}; - pos_sp_triplet.timestamp = hrt_absolute_time(); + pos_sp_triplet.timestamp = _mavlink_timesync.sync_stamp(set_position_target_local_ned.time_boot_ms * 1e3f); pos_sp_triplet.previous.valid = false; pos_sp_triplet.next.valid = false; pos_sp_triplet.current.valid = true; @@ -1077,7 +1077,7 @@ MavlinkReceiver::handle_message_set_actuator_control_target(mavlink_message_t *m offboard_control_mode.ignore_velocity = true; offboard_control_mode.ignore_acceleration_force = true; - offboard_control_mode.timestamp = hrt_absolute_time(); + offboard_control_mode.timestamp = _mavlink_timesync.sync_stamp(set_actuator_control_target.time_usec * 1e3f); if (_offboard_control_mode_pub == nullptr) { _offboard_control_mode_pub = orb_advertise(ORB_ID(offboard_control_mode), &offboard_control_mode); @@ -1301,7 +1301,7 @@ MavlinkReceiver::handle_message_set_attitude_target(mavlink_message_t *msg) _offboard_control_mode.ignore_velocity = true; _offboard_control_mode.ignore_acceleration_force = true; - _offboard_control_mode.timestamp = hrt_absolute_time(); + _offboard_control_mode.timestamp = _mavlink_timesync.sync_stamp(set_attitude_target.time_boot_ms * 1e3f); if (_offboard_control_mode_pub == nullptr) { _offboard_control_mode_pub = orb_advertise(ORB_ID(offboard_control_mode), &_offboard_control_mode); @@ -1325,7 +1325,7 @@ MavlinkReceiver::handle_message_set_attitude_target(mavlink_message_t *msg) /* Publish attitude setpoint if attitude and thrust ignore bits are not set */ if (!(_offboard_control_mode.ignore_attitude)) { vehicle_attitude_setpoint_s att_sp = {}; - att_sp.timestamp = hrt_absolute_time(); + att_sp.timestamp = _mavlink_timesync.sync_stamp(set_attitude_target.time_boot_ms * 1e3f); if (!ignore_attitude_msg) { // only copy att sp if message contained new data matrix::Quatf q(set_attitude_target.q); @@ -1355,7 +1355,7 @@ MavlinkReceiver::handle_message_set_attitude_target(mavlink_message_t *msg) ///XXX add support for ignoring individual axes if (!(_offboard_control_mode.ignore_bodyrate)) { vehicle_rates_setpoint_s rates_sp = {}; - rates_sp.timestamp = hrt_absolute_time(); + rates_sp.timestamp = _mavlink_timesync.sync_stamp(set_attitude_target.time_boot_ms * 1e3f); if (!ignore_bodyrate_msg) { // only copy att rates sp if message contained new data rates_sp.roll = set_attitude_target.body_roll_rate; @@ -1390,7 +1390,7 @@ MavlinkReceiver::handle_message_radio_status(mavlink_message_t *msg) struct telemetry_status_s &tstatus = _mavlink->get_rx_status(); - tstatus.timestamp = hrt_absolute_time(); + tstatus.timestamp = _mavlink_timesync.sync_stamp(tstatus.timestamp); tstatus.telem_time = tstatus.timestamp; /* tstatus.heartbeat_time is set by system heartbeats */ tstatus.type = telemetry_status_s::TELEMETRY_STATUS_RADIO_TYPE_3DR_RADIO; @@ -1611,7 +1611,7 @@ MavlinkReceiver::handle_message_obstacle_distance(mavlink_message_t *msg) mavlink_msg_obstacle_distance_decode(msg, &mavlink_obstacle_distance); obstacle_distance_s obstacle_distance = {}; - obstacle_distance.timestamp = hrt_absolute_time(); + obstacle_distance.timestamp = _mavlink_timesync.sync_stamp(mavlink_obstacle_distance.time_usec); obstacle_distance.sensor_type = mavlink_obstacle_distance.sensor_type; memcpy(obstacle_distance.distances, mavlink_obstacle_distance.distances, sizeof(obstacle_distance.distances)); obstacle_distance.increment = mavlink_obstacle_distance.increment; @@ -1635,7 +1635,7 @@ MavlinkReceiver::handle_message_trajectory_representation_waypoints(mavlink_mess struct vehicle_trajectory_waypoint_s trajectory_waypoint = {}; - trajectory_waypoint.timestamp = hrt_absolute_time(); + trajectory_waypoint.timestamp = _mavlink_timesync.sync_stamp(trajectory.time_usec); const int number_valid_points = trajectory.valid_points; for (int i = 0; i < vehicle_trajectory_waypoint_s::NUMBER_POINTS; ++i) { @@ -2121,7 +2121,7 @@ void MavlinkReceiver::handle_message_follow_target(mavlink_message_t *msg) mavlink_msg_follow_target_decode(msg, &follow_target_msg); - follow_target_topic.timestamp = hrt_absolute_time(); + follow_target_topic.timestamp = _mavlink_timesync.sync_stamp(follow_target_msg.timestamp * 1e3f); follow_target_topic.lat = follow_target_msg.lat * 1e-7; follow_target_topic.lon = follow_target_msg.lon * 1e-7; @@ -2429,8 +2429,7 @@ void MavlinkReceiver::handle_message_named_value_float(mavlink_message_t *msg) mavlink_msg_named_value_float_decode(msg, &debug_msg); - debug_topic.timestamp = hrt_absolute_time(); - debug_topic.timestamp_ms = debug_msg.time_boot_ms; + debug_topic.timestamp = _mavlink_timesync.sync_stamp(debug_msg.time_boot_ms * 1e3f); memcpy(debug_topic.key, debug_msg.name, sizeof(debug_topic.key)); debug_topic.key[sizeof(debug_topic.key) - 1] = '\0'; // enforce null termination debug_topic.value = debug_msg.value; @@ -2450,8 +2449,7 @@ void MavlinkReceiver::handle_message_debug(mavlink_message_t *msg) mavlink_msg_debug_decode(msg, &debug_msg); - debug_topic.timestamp = hrt_absolute_time(); - debug_topic.timestamp_ms = debug_msg.time_boot_ms; + debug_topic.timestamp = _mavlink_timesync.sync_stamp(debug_msg.time_boot_ms * 1e3f); debug_topic.ind = debug_msg.ind; debug_topic.value = debug_msg.value; @@ -2470,8 +2468,7 @@ void MavlinkReceiver::handle_message_debug_vect(mavlink_message_t *msg) mavlink_msg_debug_vect_decode(msg, &debug_msg); - debug_topic.timestamp = hrt_absolute_time(); - debug_topic.timestamp_us = debug_msg.time_usec; + debug_topic.timestamp = _mavlink_timesync.sync_stamp(debug_msg.time_usec); memcpy(debug_topic.name, debug_msg.name, sizeof(debug_topic.name)); debug_topic.name[sizeof(debug_topic.name) - 1] = '\0'; // enforce null termination debug_topic.x = debug_msg.x; diff --git a/src/modules/uavcan/libuavcan b/src/modules/uavcan/libuavcan index c044630390..dfcdf22eda 160000 --- a/src/modules/uavcan/libuavcan +++ b/src/modules/uavcan/libuavcan @@ -1 +1 @@ -Subproject commit c044630390370d800a22e7746cd949ddd3c59bb1 +Subproject commit dfcdf22eda16ff06847976fd6c7f40671fc92eb5