|
| 1 | +#include "log.h" |
| 2 | +#include "mavsdk.h" |
| 3 | +#include "plugins/telemetry/telemetry.h" |
| 4 | +#include "plugins/mavlink_direct/mavlink_direct.h" |
| 5 | +#include <atomic> |
| 6 | +#include <chrono> |
| 7 | +#include <future> |
| 8 | +#include <thread> |
| 9 | +#include <gtest/gtest.h> |
| 10 | + |
| 11 | +using namespace mavsdk; |
| 12 | + |
| 13 | +// Test that RC status updates arrive via SYS_STATUS messages. |
| 14 | +// This is the path used by ArduPilot where RC receiver health |
| 15 | +// is reported through the SYS_STATUS sensor flags. |
| 16 | +TEST(SystemTest, RcStatusViaSysStatus) |
| 17 | +{ |
| 18 | + Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}}; |
| 19 | + Mavsdk mavsdk_autopilot{Mavsdk::Configuration{ComponentType::Autopilot}}; |
| 20 | + |
| 21 | + ASSERT_EQ( |
| 22 | + mavsdk_groundstation.add_any_connection("udpin://0.0.0.0:15220"), |
| 23 | + ConnectionResult::Success); |
| 24 | + ASSERT_EQ( |
| 25 | + mavsdk_autopilot.add_any_connection("udpout://127.0.0.1:15220"), |
| 26 | + ConnectionResult::Success); |
| 27 | + |
| 28 | + auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); |
| 29 | + ASSERT_TRUE(maybe_system); |
| 30 | + auto system = maybe_system.value(); |
| 31 | + |
| 32 | + while (mavsdk_autopilot.systems().size() == 0) { |
| 33 | + std::this_thread::sleep_for(std::chrono::milliseconds(100)); |
| 34 | + } |
| 35 | + auto gs_system = mavsdk_autopilot.systems().at(0); |
| 36 | + |
| 37 | + auto telemetry = Telemetry{system}; |
| 38 | + auto sender = MavlinkDirect{gs_system}; |
| 39 | + |
| 40 | + auto prom = std::promise<Telemetry::RcStatus>{}; |
| 41 | + auto fut = prom.get_future(); |
| 42 | + std::atomic<bool> received{false}; |
| 43 | + |
| 44 | + auto handle = telemetry.subscribe_rc_status([&](const Telemetry::RcStatus& rc_status) { |
| 45 | + if (!received.exchange(true)) { |
| 46 | + prom.set_value(rc_status); |
| 47 | + } |
| 48 | + }); |
| 49 | + |
| 50 | + std::this_thread::sleep_for(std::chrono::milliseconds(100)); |
| 51 | + |
| 52 | + // Send SYS_STATUS with RC receiver present and healthy |
| 53 | + // MAV_SYS_STATUS_SENSOR_RC_RECEIVER = 0x10000 = 65536 |
| 54 | + const uint32_t rc_receiver_flag = 65536; |
| 55 | + MavlinkDirect::MavlinkMessage msg; |
| 56 | + msg.message_name = "SYS_STATUS"; |
| 57 | + msg.system_id = 1; |
| 58 | + msg.component_id = 1; |
| 59 | + msg.target_system_id = 0; |
| 60 | + msg.target_component_id = 0; |
| 61 | + msg.fields_json = |
| 62 | + "{\"onboard_control_sensors_present\":" + std::to_string(rc_receiver_flag) + |
| 63 | + ",\"onboard_control_sensors_enabled\":" + std::to_string(rc_receiver_flag) + |
| 64 | + ",\"onboard_control_sensors_health\":" + std::to_string(rc_receiver_flag) + |
| 65 | + ",\"load\":0,\"voltage_battery\":0,\"current_battery\":0," |
| 66 | + "\"battery_remaining\":-1,\"drop_rate_comm\":0,\"errors_comm\":0," |
| 67 | + "\"errors_count1\":0,\"errors_count2\":0,\"errors_count3\":0,\"errors_count4\":0}"; |
| 68 | + |
| 69 | + auto result = sender.send_message(msg); |
| 70 | + EXPECT_EQ(result, MavlinkDirect::Result::Success); |
| 71 | + |
| 72 | + ASSERT_EQ(fut.wait_for(std::chrono::seconds(5)), std::future_status::ready); |
| 73 | + |
| 74 | + auto rc_status = fut.get(); |
| 75 | + // RC receiver is healthy → is_available should be true |
| 76 | + EXPECT_TRUE(rc_status.is_available); |
| 77 | + |
| 78 | + telemetry.unsubscribe_rc_status(handle); |
| 79 | +} |
| 80 | + |
| 81 | +// Test that RC status updates arrive via RC_CHANNELS messages. |
| 82 | +// This is the path used by PX4 where RC signal strength is |
| 83 | +// reported through the RC_CHANNELS message rssi field. |
| 84 | +TEST(SystemTest, RcStatusViaRcChannels) |
| 85 | +{ |
| 86 | + Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}}; |
| 87 | + Mavsdk mavsdk_autopilot{Mavsdk::Configuration{ComponentType::Autopilot}}; |
| 88 | + |
| 89 | + ASSERT_EQ( |
| 90 | + mavsdk_groundstation.add_any_connection("udpin://0.0.0.0:15221"), |
| 91 | + ConnectionResult::Success); |
| 92 | + ASSERT_EQ( |
| 93 | + mavsdk_autopilot.add_any_connection("udpout://127.0.0.1:15221"), |
| 94 | + ConnectionResult::Success); |
| 95 | + |
| 96 | + auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); |
| 97 | + ASSERT_TRUE(maybe_system); |
| 98 | + auto system = maybe_system.value(); |
| 99 | + |
| 100 | + while (mavsdk_autopilot.systems().size() == 0) { |
| 101 | + std::this_thread::sleep_for(std::chrono::milliseconds(100)); |
| 102 | + } |
| 103 | + auto gs_system = mavsdk_autopilot.systems().at(0); |
| 104 | + |
| 105 | + auto telemetry = Telemetry{system}; |
| 106 | + auto sender = MavlinkDirect{gs_system}; |
| 107 | + |
| 108 | + auto prom = std::promise<Telemetry::RcStatus>{}; |
| 109 | + auto fut = prom.get_future(); |
| 110 | + std::atomic<bool> received{false}; |
| 111 | + |
| 112 | + auto handle = telemetry.subscribe_rc_status([&](const Telemetry::RcStatus& rc_status) { |
| 113 | + // Wait for a callback that has signal_strength set (from RC_CHANNELS) |
| 114 | + if (rc_status.signal_strength_percent > 0.0f && !received.exchange(true)) { |
| 115 | + prom.set_value(rc_status); |
| 116 | + } |
| 117 | + }); |
| 118 | + |
| 119 | + std::this_thread::sleep_for(std::chrono::milliseconds(100)); |
| 120 | + |
| 121 | + // Send RC_CHANNELS with rssi = 200 (out of 255) |
| 122 | + MavlinkDirect::MavlinkMessage msg; |
| 123 | + msg.message_name = "RC_CHANNELS"; |
| 124 | + msg.system_id = 1; |
| 125 | + msg.component_id = 1; |
| 126 | + msg.target_system_id = 0; |
| 127 | + msg.target_component_id = 0; |
| 128 | + msg.fields_json = |
| 129 | + R"({"time_boot_ms":1000,"chancount":8,"chan1_raw":1500,"chan2_raw":1500,)" |
| 130 | + R"("chan3_raw":1500,"chan4_raw":1500,"chan5_raw":0,"chan6_raw":0,)" |
| 131 | + R"("chan7_raw":0,"chan8_raw":0,"chan9_raw":0,"chan10_raw":0,)" |
| 132 | + R"("chan11_raw":0,"chan12_raw":0,"chan13_raw":0,"chan14_raw":0,)" |
| 133 | + R"("chan15_raw":0,"chan16_raw":0,"chan17_raw":0,"chan18_raw":0,"rssi":200})"; |
| 134 | + |
| 135 | + auto result = sender.send_message(msg); |
| 136 | + EXPECT_EQ(result, MavlinkDirect::Result::Success); |
| 137 | + |
| 138 | + ASSERT_EQ(fut.wait_for(std::chrono::seconds(5)), std::future_status::ready); |
| 139 | + |
| 140 | + auto rc_status = fut.get(); |
| 141 | + // rssi is stored directly as signal_strength_percent (raw value 0-254) |
| 142 | + EXPECT_FLOAT_EQ(rc_status.signal_strength_percent, 200.0f); |
| 143 | + |
| 144 | + telemetry.unsubscribe_rc_status(handle); |
| 145 | +} |
| 146 | + |
| 147 | +// Test that RC status correctly reports unavailable when |
| 148 | +// SYS_STATUS reports RC receiver not healthy. |
| 149 | +TEST(SystemTest, RcStatusUnavailableViaSysStatus) |
| 150 | +{ |
| 151 | + Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}}; |
| 152 | + Mavsdk mavsdk_autopilot{Mavsdk::Configuration{ComponentType::Autopilot}}; |
| 153 | + |
| 154 | + ASSERT_EQ( |
| 155 | + mavsdk_groundstation.add_any_connection("udpin://0.0.0.0:15222"), |
| 156 | + ConnectionResult::Success); |
| 157 | + ASSERT_EQ( |
| 158 | + mavsdk_autopilot.add_any_connection("udpout://127.0.0.1:15222"), |
| 159 | + ConnectionResult::Success); |
| 160 | + |
| 161 | + auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); |
| 162 | + ASSERT_TRUE(maybe_system); |
| 163 | + auto system = maybe_system.value(); |
| 164 | + |
| 165 | + while (mavsdk_autopilot.systems().size() == 0) { |
| 166 | + std::this_thread::sleep_for(std::chrono::milliseconds(100)); |
| 167 | + } |
| 168 | + auto gs_system = mavsdk_autopilot.systems().at(0); |
| 169 | + |
| 170 | + auto telemetry = Telemetry{system}; |
| 171 | + auto sender = MavlinkDirect{gs_system}; |
| 172 | + |
| 173 | + auto prom = std::promise<Telemetry::RcStatus>{}; |
| 174 | + auto fut = prom.get_future(); |
| 175 | + std::atomic<bool> received{false}; |
| 176 | + |
| 177 | + auto handle = telemetry.subscribe_rc_status([&](const Telemetry::RcStatus& rc_status) { |
| 178 | + if (!received.exchange(true)) { |
| 179 | + prom.set_value(rc_status); |
| 180 | + } |
| 181 | + }); |
| 182 | + |
| 183 | + std::this_thread::sleep_for(std::chrono::milliseconds(100)); |
| 184 | + |
| 185 | + // Send SYS_STATUS with RC receiver present but NOT healthy |
| 186 | + // MAV_SYS_STATUS_SENSOR_RC_RECEIVER = 0x10000 = 65536 |
| 187 | + const uint32_t rc_receiver_flag = 65536; |
| 188 | + MavlinkDirect::MavlinkMessage msg; |
| 189 | + msg.message_name = "SYS_STATUS"; |
| 190 | + msg.system_id = 1; |
| 191 | + msg.component_id = 1; |
| 192 | + msg.target_system_id = 0; |
| 193 | + msg.target_component_id = 0; |
| 194 | + msg.fields_json = |
| 195 | + "{\"onboard_control_sensors_present\":" + std::to_string(rc_receiver_flag) + |
| 196 | + ",\"onboard_control_sensors_enabled\":" + std::to_string(rc_receiver_flag) + |
| 197 | + ",\"onboard_control_sensors_health\":0" |
| 198 | + ",\"load\":0,\"voltage_battery\":0,\"current_battery\":0," |
| 199 | + "\"battery_remaining\":-1,\"drop_rate_comm\":0,\"errors_comm\":0," |
| 200 | + "\"errors_count1\":0,\"errors_count2\":0,\"errors_count3\":0,\"errors_count4\":0}"; |
| 201 | + |
| 202 | + auto result = sender.send_message(msg); |
| 203 | + EXPECT_EQ(result, MavlinkDirect::Result::Success); |
| 204 | + |
| 205 | + ASSERT_EQ(fut.wait_for(std::chrono::seconds(5)), std::future_status::ready); |
| 206 | + |
| 207 | + auto rc_status = fut.get(); |
| 208 | + // RC receiver present but not healthy → is_available should be false |
| 209 | + EXPECT_FALSE(rc_status.is_available); |
| 210 | + |
| 211 | + telemetry.unsubscribe_rc_status(handle); |
| 212 | +} |
0 commit comments