diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 3d2f43c80e..74d8d00fb0 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -2267,7 +2267,7 @@ Mavlink::task_main(int argc, char *argv[]) /* switch HIL mode if required */ set_hil_enabled(status.hil_state == vehicle_status_s::HIL_STATE_ON); - set_manual_input_mode_generation(status.rc_input_mode == vehicle_status_s::RC_IN_MODE_GENERATED); + set_generate_virtual_rc_input(status.rc_input_mode == vehicle_status_s::RC_IN_MODE_GENERATED); if (_mode == MAVLINK_MODE_IRIDIUM) { diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index d767b610b5..7c3ab0f7fa 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -302,7 +302,7 @@ public: * * @param generation_enabled If set to true, generate RC_INPUT messages */ - void set_manual_input_mode_generation(bool generation_enabled) { _generate_rc = generation_enabled; } + void set_generate_virtual_rc_input(bool generation_enabled) { _generate_rc = generation_enabled; } /** * Set communication protocol for this mavlink instance @@ -314,7 +314,7 @@ public: * * @return true if manual inputs should generate RC data */ - bool get_manual_input_mode_generation() { return _generate_rc; } + bool should_generate_virtual_rc_input() { return _generate_rc; } /** * This is the beginning of a MAVLINK_START_UART_SEND/MAVLINK_END_UART_SEND transaction diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 71c8849cd5..afd21491f3 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -1936,7 +1936,7 @@ MavlinkReceiver::handle_message_manual_control(mavlink_message_t *msg) return; } - if (_mavlink->get_manual_input_mode_generation()) { + if (_mavlink->should_generate_virtual_rc_input()) { input_rc_s rc{}; rc.timestamp = hrt_absolute_time();