diff --git a/msg/input_rc.msg b/msg/input_rc.msg index 0896bdd34f..4df163fb49 100644 --- a/msg/input_rc.msg +++ b/msg/input_rc.msg @@ -15,7 +15,6 @@ uint8 RC_INPUT_SOURCE_PX4IO_SUMD = 13 uint8 RC_INPUT_MAX_CHANNELS = 18 # Maximum number of R/C input channels in the system. S.Bus has up to 18 channels. -uint64 timestamp_publication # publication time uint64 timestamp_last_signal # last valid reception time uint32 channel_count # number of channels actually being seen int32 rssi # receive signal strength indicator (RSSI): < 0: Undefined, 0: no signal, 100: full reception diff --git a/src/drivers/navio_sysfs_rc_in/navio_sysfs_rc_in.cpp b/src/drivers/navio_sysfs_rc_in/navio_sysfs_rc_in.cpp index 598f354ba4..07818f5e88 100644 --- a/src/drivers/navio_sysfs_rc_in/navio_sysfs_rc_in.cpp +++ b/src/drivers/navio_sysfs_rc_in/navio_sysfs_rc_in.cpp @@ -197,7 +197,7 @@ void RcInput::_measure(void) } ts = hrt_absolute_time(); - _data.timestamp_publication = ts; + _data.timestamp = ts; _data.timestamp_last_signal = ts; _data.channel_count = _channels; _data.rssi = 100; diff --git a/src/drivers/pwm_out_rc_in/pwm_out_rc_in.cpp b/src/drivers/pwm_out_rc_in/pwm_out_rc_in.cpp index e7756c3d8f..b9fa461aaf 100644 --- a/src/drivers/pwm_out_rc_in/pwm_out_rc_in.cpp +++ b/src/drivers/pwm_out_rc_in/pwm_out_rc_in.cpp @@ -323,7 +323,7 @@ void handle_message(mavlink_message_t *rc_message) { mavlink_rc_channels_t rc; mavlink_msg_rc_channels_decode(rc_message, &rc); - _rc.timestamp_publication = hrt_absolute_time(); + _rc.timestamp = hrt_absolute_time(); _rc.timestamp_last_signal = hrt_absolute_time(); _rc.channel_count = rc.chancount; _rc.rc_lost = false; diff --git a/src/drivers/px4fmu/fmu.cpp b/src/drivers/px4fmu/fmu.cpp index 523be4b022..895d172396 100644 --- a/src/drivers/px4fmu/fmu.cpp +++ b/src/drivers/px4fmu/fmu.cpp @@ -810,8 +810,8 @@ PX4FMU::fill_rc_in(uint16_t raw_rc_count, } } - _rc_in.timestamp_publication = now; - _rc_in.timestamp_last_signal = _rc_in.timestamp_publication; + _rc_in.timestamp = now; + _rc_in.timestamp_last_signal = _rc_in.timestamp; _rc_in.rc_ppm_frame_length = 0; /* fake rssi if no value was provided */ diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index 736412ac73..b03b7f319b 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -1839,7 +1839,7 @@ PX4IO::io_get_raw_rc_input(rc_input_values &input_rc) _rc_chan_count = channel_count; - input_rc.timestamp_publication = hrt_absolute_time(); + input_rc.timestamp = hrt_absolute_time(); input_rc.rc_ppm_frame_length = regs[PX4IO_P_RAW_RC_DATA]; @@ -1868,7 +1868,7 @@ PX4IO::io_get_raw_rc_input(rc_input_values &input_rc) /* rc_lost has to be set before the call to this function */ if (!input_rc.rc_lost && !input_rc.rc_failsafe) { - _rc_last_valid = input_rc.timestamp_publication; + _rc_last_valid = input_rc.timestamp; } input_rc.timestamp_last_signal = _rc_last_valid; diff --git a/src/drivers/snapdragon_rc_pwm/snapdragon_rc_pwm.cpp b/src/drivers/snapdragon_rc_pwm/snapdragon_rc_pwm.cpp index bda765783e..f676c46206 100644 --- a/src/drivers/snapdragon_rc_pwm/snapdragon_rc_pwm.cpp +++ b/src/drivers/snapdragon_rc_pwm/snapdragon_rc_pwm.cpp @@ -234,7 +234,7 @@ void set_pwm_output(mavlink_actuator_control_target_t *actuator_controls) void send_rc_mavlink() { mavlink_rc_channels_t rc_message; - rc_message.time_boot_ms = _rc.timestamp_publication / 1000; + rc_message.time_boot_ms = _rc.timestamp / 1000; rc_message.chancount = _rc.channel_count; rc_message.chan1_raw = (_rc.channel_count > 0) ? _rc.values[0] : UINT16_MAX; rc_message.chan2_raw = (_rc.channel_count > 1) ? _rc.values[1] : UINT16_MAX; diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index 59ac1ecd9f..2d632d0b8c 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -2645,7 +2645,7 @@ protected: /* send RC channel data and RSSI */ mavlink_rc_channels_t msg; - msg.time_boot_ms = rc.timestamp_publication / 1000; + msg.time_boot_ms = rc.timestamp / 1000; msg.chancount = rc.channel_count; msg.chan1_raw = (rc.channel_count > 0) ? rc.values[0] : UINT16_MAX; msg.chan2_raw = (rc.channel_count > 1) ? rc.values[1] : UINT16_MAX; diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 25048257fc..e45b960818 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -1277,9 +1277,9 @@ MavlinkReceiver::handle_message_rc_channels_override(mavlink_message_t *msg) struct rc_input_values rc = {}; - rc.timestamp_publication = hrt_absolute_time(); + rc.timestamp = hrt_absolute_time(); - rc.timestamp_last_signal = rc.timestamp_publication; + rc.timestamp_last_signal = rc.timestamp; rc.channel_count = 8; @@ -1336,8 +1336,8 @@ MavlinkReceiver::handle_message_manual_control(mavlink_message_t *msg) if (_mavlink->get_manual_input_mode_generation()) { struct rc_input_values rc = {}; - rc.timestamp_publication = hrt_absolute_time(); - rc.timestamp_last_signal = rc.timestamp_publication; + rc.timestamp = hrt_absolute_time(); + rc.timestamp_last_signal = rc.timestamp; rc.channel_count = 8; rc.rc_failsafe = false; diff --git a/src/modules/simulator/simulator_mavlink.cpp b/src/modules/simulator/simulator_mavlink.cpp index 1fd50bbe57..003f3fe9c2 100644 --- a/src/modules/simulator/simulator_mavlink.cpp +++ b/src/modules/simulator/simulator_mavlink.cpp @@ -114,8 +114,8 @@ void Simulator::send_controls() static void fill_rc_input_msg(struct rc_input_values *rc, mavlink_rc_channels_t *rc_channels) { - rc->timestamp_publication = hrt_absolute_time(); - rc->timestamp_last_signal = hrt_absolute_time(); + rc->timestamp = hrt_absolute_time(); + rc->timestamp_last_signal = rc->timestamp; rc->channel_count = rc_channels->chancount; rc->rssi = rc_channels->rssi; diff --git a/src/platforms/qurt/fc_addon/rc_receiver/rc_receiver_main.cpp b/src/platforms/qurt/fc_addon/rc_receiver/rc_receiver_main.cpp index 8f3e194ec9..c2269a88ff 100644 --- a/src/platforms/qurt/fc_addon/rc_receiver/rc_receiver_main.cpp +++ b/src/platforms/qurt/fc_addon/rc_receiver/rc_receiver_main.cpp @@ -248,8 +248,8 @@ void task_main(int argc, char *argv[]) // populate the input_rc_s structure if (ret == 0) { - _rc_in.timestamp_publication = ts; - _rc_in.timestamp_last_signal = _rc_in.timestamp_publication; + _rc_in.timestamp = ts; + _rc_in.timestamp_last_signal = _rc_in.timestamp; _rc_in.channel_count = num_channels; // TODO - need to add support for RSSI, failsafe mode